Setting initial joint position
How can I specify that my robot model spawned starts in a specific state ?
How can I specify that my robot model spawned starts in a specific state ?
If you are launching from ROS,
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model"
args="-param robot_description -urdf -model robot
-J ARM/Shoulder/X5_9 1.1" />
spawns this *.urdf into Gazebo with the ARM/Shoulder/X5_9
joint set to an initial position of 1.1 radians.
*.urdf (fragment):
...
<joint name="ARM/Shoulder/X5_9" type="revolute">
<parent link="hebi_x5_9_16Z"/>
<child link="a_2038_02_6Z"/>
<axis xyz="-2.77554010017e-17 -1.66533454e-16 1.0"/>
<dynamics damping="0.5" friction="0.06"/>
<limit effort="100" lower="0" upper="+1.1" velocity="100"/>
<origin rpy="0.0 -2.77555756e-17 0.0" xyz="-5.63687556453e-17 2.34257058104e-17 0.03"/>
</joint>
...
Note: If you want to dig deeper, check out these lines in ~/gazebo_ros/gazebo_interface.py
:
https://github.com/ros-simulation/gaz...
Asked: 2018-07-25 08:55:55 -0600
Seen: 6,384 times
Last updated: Jul 26 '18
Issues importing Autodesk dae file - Segmentation Fault
Publishing JointStates in ROS with Gazebo
spawning a robot from urdf with origin parameters through ros in gazebo 1.8
Gazebo 7.8.1 Problem with turtlebot spawn
Declare and pass parameters in SDF files while spawning models
Spawn_model with ROS Groovy and Gazebo version 1.9.5.
Unable to launch Gazebo simulation, showing error "[spawn_gazebo_model-4] process has died..."
How to spawn sdf object in Ignition Gazebo?
Gazebo in Groovy (1.2.5) does not use translation when spawning urdf model [closed]