Actuated or not, RViz reflects the current transform tree. If it's visualizing the robot but doesn't show updated poses, it's because RViz doesn't know about them. Do you have a robot_state_publisher
node running? Here's an example from the tutorial:
<launch>
<!-- Load the urdf into the parameter server. -->
<param name="my_robot_description" textfile="$(find mypackage)/urdf/robotmodel.xml"/>
<node pkg="robot_state_publisher" type="robot_state_publisher" name="rob_st_pub" >
<remap from="robot_description" to="my_robot_description" />
<remap from="joint_states" to="different_joint_states" />
</node>
</launch>
If there's no friction, damping, or actuator, there's nothing to stop the joint once it starts moving, so what you describe sounds like expected behavior. If the behavior doesn't make sense--even for a fricitonless world-- then some of the other physical parameters may be off, but we'll need more information to track down the problem. The URDF joint wiki provides information on how to add damping or friction to a joint:
<joint name="my_joint" type="floating">
<origin xyz="0 0 1" rpy="0 0 3.1416"/>
<parent link="link1"/>
<child link="link2"/>
<calibration rising="0.0"/>
<dynamics damping="0.7" friction="0.0"/> # Make one of these non-zero
<limit effort="30" velocity="1.0" lower="-2.2" upper="0.7" />
<safety_controller k_velocity="10" k_position="15" soft_lower_limit="-2.0" soft_upper_limit="0.5" />
</joint>
If you want to see the casters move properly, you'll need surface friction between them and the ground. The Gazebo friction tutorial provides an example and some helpful links. You may also consider just modeling them as frictionless spheres, depending on your application.
Update 1
You can add actuators without using them, so the joint remains free to move. Since you're using a JointStateController
, just add a transmission to each movable joint in ridgeback.urdf.xacro
. Here's an example for cargo_cart_joint
:
...
<joint name="cargo_cart_joint" type="revolute">
<origin xyz="0 0 0.025" rpy="0 0 0" />
<parent link="tow_hitch_link"/>
<child link="cargo_cart_link" />
<axis xyz="0 0 1" />
<limit lower="-${PI/2}" upper="${PI/2}" velocity="0" effort="0"/>
<dynamics damping="${damping_coef}" friction="${friction_coef}" />
</joint>
<transmission name="cargo_cart_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="cargo_cart_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="cargo_cart_joint_actuator">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
...
Then, ridgeback_joint_publisher
will publish the states of those joints. It only finds joints "registered to a hardware_interface::JointStateInterface
" as mentioned in the ros_control
wiki. You'll also have to get rid of joint_state_publisher_gui
in empty_world.launch
as that will collide and cause the published joint state to flip back and forth.
Update 2
I agree that revolute joints seem to behave as expected, though I don't know why the continuous joints don't. In any case, I recommend adding some trailing distance to the casters to encourage "following" behavior, and adding damping/friction to address the drift/skid issue.
I changed your URDF file as ... (more)
Please do not link to images on Google drive. They tend to disappear. Please attach your images directly to the post. You have sufficient karma to do that.