GazeboRosActuatorArray controller. More...
|
Classes | |
| struct | gazebo::GazeboJointProperties |
| GazeboRosActuatorArray controller. More... | |
| class | gazebo::GazeboRosActuatorArray |
| struct | gazebo::MimicJointProperties |
GazeboRosActuatorArray controller.
This controller requires to a model as its parent. This plugin controls a number of independent actuators (probably in some sort of kinematic chain), where each actuator accepts a position command. Such things as a Pioneer Arm or Manoi may be modeled with such. Each actuator is controlled inside Gazebo with a PID loop (courtesy of control_toolbox::Pid). This PID can be tuned to match the performance of the real system. This controller publishes the state of each actuator via sensor_msgs::JointState messages to the {robot_namespace}/joint_states topic, and receives joint commands via a sensor_msgs::JointState message on the {robot_namespace}/command topic.
When specifying the controller, each joint that is to be controlled should be placed inside a <joint> tag. The joint name (required), home position (optional), and PID parameters (optional) are specified inside each <joint> block. See below for an example. Maximum joint efforts (forces/torques), and joint velocities are read from the URDF/robot definition.
Example Usage:
<model:physical name="some_fancy_model">
<controller:gazebo_ros_actuator_array name="actuator_array_controller" plugin="libgazebo_ros_actuator_array.so">
<alwaysOn>true</alwaysOn>
<updateRate>30.0</updateRate>
<robotParam>robot_description</robotParam>
<joint>
<name>joint01</name>
<home>0.0</home>
<p>10.0</p>
<i>0.0</i>
<d>0.0</d>
<iClamp>0.0</iClamp>
</joint>
<joint>
<name>joint02</name>
<home>1.57080</home>
<p>20.0</p>
<i>0.0</i>
<d>0.0</d>
<iClamp>0.0</iClamp>
</joint>
<joint>
<name>joint03</name>
<home>3.14159</home>
<p>10.0</p>
<i>0.0</i>
<d>2.0</d>
<iClamp>0.0</iClamp>
</joint>
</controller:gazebo_ros_actuator_array>
</model:physical>