5 #include <pr2_mechanism_msgs/LoadController.h> 7 #include <boost/scoped_ptr.hpp> 8 #include <sensor_msgs/JointState.h> 9 #include <kdl/chain.hpp> 18 pr2_mechanism_msgs::LoadController::Response& resp);
21 boost::scoped_ptr<realtime_tools::RealtimePublisher<sensor_msgs::JointState> >
pub_;
pr2_mechanism_model::Chain chain_
ros::Time time_of_last_cycle_
void starting()
Controller startup in realtime.
boost::scoped_ptr< realtime_tools::RealtimePublisher< sensor_msgs::JointState > > pub_
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Controller initialization in non-realtime.
void stopping()
Controller stopping in realtime.
void update()
Controller update loop in realtime.
pr2_mechanism_model::JointState * joint_state_
pr2_mechanism_model::RobotState * robot_
bool serviceCallback(pr2_mechanism_msgs::LoadController::Request &req, pr2_mechanism_msgs::LoadController::Response &resp)
Service call.