test_controller.h
Go to the documentation of this file.
4 #include <ros/ros.h>
5 #include <pr2_mechanism_msgs/LoadController.h>
7 #include <boost/scoped_ptr.hpp>
8 #include <sensor_msgs/JointState.h>
9 #include <kdl/chain.hpp>
10 
11 
12 namespace my_controller_ns{
13 
15 {
16 private:
17  bool serviceCallback(pr2_mechanism_msgs::LoadController::Request& req,
18  pr2_mechanism_msgs::LoadController::Response& resp);
19 
21  boost::scoped_ptr<realtime_tools::RealtimePublisher<sensor_msgs::JointState> > pub_;
27  double max_effort_;
28  unsigned int counter_;
29 
30 public:
32  ros::NodeHandle &n);
33  void starting();
34  void update();
35  void stopping();
36 };
37 }
pr2_mechanism_model::Chain chain_
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.


pr2_controller_manager
Author(s): Eric Berger berger@willowgarage.com, Stuart Glaser, Wim Meeussen
autogenerated on Fri Jun 7 2019 22:04:28