#include <srh_syntouch_controllers.hpp>
Public Member Functions | |
bool | init (pr2_mechanism_model::RobotState *robot, const std::string &joint_name) |
bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
SrhSyntouchController () | |
virtual void | starting () |
virtual void | update () |
Issues commands to the joint. Should be called at regular intervals. | |
~SrhSyntouchController () | |
Private Attributes | |
sr_actuator::SrActuator * | actuator_ |
boost::shared_ptr < realtime_tools::RealtimePublisher < sr_robot_msgs::JointControllerState > > | controller_state_publisher_ |
Definition at line 37 of file srh_syntouch_controllers.hpp.
Definition at line 40 of file srh_syntouch_controllers.cpp.
Definition at line 45 of file srh_syntouch_controllers.cpp.
bool controller::SrhSyntouchController::init | ( | pr2_mechanism_model::RobotState * | robot, |
const std::string & | joint_name | ||
) |
Definition at line 50 of file srh_syntouch_controllers.cpp.
bool controller::SrhSyntouchController::init | ( | pr2_mechanism_model::RobotState * | robot, |
ros::NodeHandle & | n | ||
) | [virtual] |
Reimplemented from controller::SrController.
Definition at line 79 of file srh_syntouch_controllers.cpp.
void controller::SrhSyntouchController::starting | ( | ) | [virtual] |
Reimplemented from controller::SrController.
Definition at line 94 of file srh_syntouch_controllers.cpp.
void controller::SrhSyntouchController::update | ( | void | ) | [virtual] |
Issues commands to the joint. Should be called at regular intervals.
Reimplemented from controller::SrController.
Definition at line 101 of file srh_syntouch_controllers.cpp.
Definition at line 58 of file srh_syntouch_controllers.hpp.
boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::JointControllerState> > controller::SrhSyntouchController::controller_state_publisher_ [private] |
Reimplemented from controller::SrController.
Definition at line 56 of file srh_syntouch_controllers.hpp.