$search
#include <test_controller.h>
Public Member Functions | |
bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
Controller initialization in non-realtime. | |
void | starting () |
Controller startup in realtime. | |
void | stopping () |
Controller stopping in realtime. | |
void | update () |
Controller update loop in realtime. | |
Private Member Functions | |
bool | serviceCallback (pr2_mechanism_msgs::LoadController::Request &req, pr2_mechanism_msgs::LoadController::Response &resp) |
Service call. | |
Private Attributes | |
pr2_mechanism_model::Chain | chain_ |
unsigned int | counter_ |
pr2_mechanism_model::JointState * | joint_state_ |
KDL::Chain | kdl_chain_ |
double | max_effort_ |
boost::scoped_ptr < realtime_tools::RealtimePublisher < sensor_msgs::JointState > > | pub_ |
pr2_mechanism_model::RobotState * | robot_ |
ros::ServiceServer | srv_ |
ros::Time | time_of_last_cycle_ |
Definition at line 14 of file test_controller.h.
bool MyControllerClass::init | ( | pr2_mechanism_model::RobotState * | robot, | |
ros::NodeHandle & | n | |||
) | [virtual] |
Controller initialization in non-realtime.
Implements pr2_controller_interface::Controller.
Definition at line 9 of file test_controller.cpp.
bool MyControllerClass::serviceCallback | ( | pr2_mechanism_msgs::LoadController::Request & | req, | |
pr2_mechanism_msgs::LoadController::Response & | resp | |||
) | [private] |
Service call.
Definition at line 122 of file test_controller.cpp.
void MyControllerClass::starting | ( | ) | [virtual] |
Controller startup in realtime.
Reimplemented from pr2_controller_interface::Controller.
Definition at line 86 of file test_controller.cpp.
void MyControllerClass::stopping | ( | ) | [virtual] |
Controller stopping in realtime.
Reimplemented from pr2_controller_interface::Controller.
Definition at line 117 of file test_controller.cpp.
void MyControllerClass::update | ( | void | ) | [virtual] |
Controller update loop in realtime.
Implements pr2_controller_interface::Controller.
Definition at line 94 of file test_controller.cpp.
Definition at line 24 of file test_controller.h.
unsigned int my_controller_ns::MyControllerClass::counter_ [private] |
Definition at line 28 of file test_controller.h.
Definition at line 23 of file test_controller.h.
Definition at line 25 of file test_controller.h.
double my_controller_ns::MyControllerClass::max_effort_ [private] |
Definition at line 27 of file test_controller.h.
boost::scoped_ptr<realtime_tools::RealtimePublisher<sensor_msgs::JointState> > my_controller_ns::MyControllerClass::pub_ [private] |
Definition at line 21 of file test_controller.h.
Definition at line 22 of file test_controller.h.
Definition at line 20 of file test_controller.h.
Definition at line 26 of file test_controller.h.