Controller that publishes the state of all joints in a robot. More...
#include <joint_state_controller.h>

Public Member Functions | |
| virtual bool | init (hardware_interface::JointStateInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) |
| JointStateController () | |
| virtual void | starting (const ros::Time &time) |
| virtual void | stopping (const ros::Time &) |
| virtual void | update (const ros::Time &time, const ros::Duration &) |
Private Member Functions | |
| void | addExtraJoints (const ros::NodeHandle &nh, sensor_msgs::JointState &msg) |
Private Attributes | |
| std::vector < hardware_interface::JointStateHandle > | joint_state_ |
| ros::Time | last_publish_time_ |
| unsigned int | num_hw_joints_ |
| Number of joints present in the JointStateInterface, excluding extra joints. | |
| double | publish_rate_ |
| boost::shared_ptr < realtime_tools::RealtimePublisher < sensor_msgs::JointState > > | realtime_pub_ |
Controller that publishes the state of all joints in a robot.
This controller publishes the state of all resources registered to a hardware_interface::JointStateInterface to a topic of type sensor_msgs/JointState. The following is a basic configuration of the controller.
joint_state_controller: type: joint_state_controller/JointStateController publish_rate: 50
It's possible to optionally specify a set of extra joints not contained in a hardware_interface::JointStateInterface with custom (and static) default values. The following is an example configuration specifying extra joints.
joint_state_controller: type: joint_state_controller/JointStateController publish_rate: 50 extra_joints: - name: 'extra1' position: 10.0 velocity: 20.0 effort: 30.0 - name: 'extra2' position: -10.0 - name: 'extra3'
An unspecified position, velocity or acceleration defaults to zero.
Definition at line 79 of file joint_state_controller.h.
Definition at line 82 of file joint_state_controller.h.
| void joint_state_controller::JointStateController::addExtraJoints | ( | const ros::NodeHandle & | nh, |
| sensor_msgs::JointState & | msg | ||
| ) | [private] |
Definition at line 105 of file joint_state_controller.cpp.
| bool joint_state_controller::JointStateController::init | ( | hardware_interface::JointStateInterface * | hw, |
| ros::NodeHandle & | root_nh, | ||
| ros::NodeHandle & | controller_nh | ||
| ) | [virtual] |
Reimplemented from controller_interface::Controller< hardware_interface::JointStateInterface >.
Definition at line 40 of file joint_state_controller.cpp.
| void joint_state_controller::JointStateController::starting | ( | const ros::Time & | time | ) | [virtual] |
Reimplemented from controller_interface::ControllerBase.
Definition at line 72 of file joint_state_controller.cpp.
| void joint_state_controller::JointStateController::stopping | ( | const ros::Time & | ) | [virtual] |
Reimplemented from controller_interface::ControllerBase.
Definition at line 102 of file joint_state_controller.cpp.
| void joint_state_controller::JointStateController::update | ( | const ros::Time & | time, |
| const ros::Duration & | |||
| ) | [virtual] |
Implements controller_interface::ControllerBase.
Definition at line 78 of file joint_state_controller.cpp.
std::vector<hardware_interface::JointStateHandle> joint_state_controller::JointStateController::joint_state_ [private] |
Definition at line 92 of file joint_state_controller.h.
Definition at line 94 of file joint_state_controller.h.
unsigned int joint_state_controller::JointStateController::num_hw_joints_ [private] |
Number of joints present in the JointStateInterface, excluding extra joints.
Definition at line 96 of file joint_state_controller.h.
double joint_state_controller::JointStateController::publish_rate_ [private] |
Definition at line 95 of file joint_state_controller.h.
boost::shared_ptr<realtime_tools::RealtimePublisher<sensor_msgs::JointState> > joint_state_controller::JointStateController::realtime_pub_ [private] |
Definition at line 93 of file joint_state_controller.h.