#include <force_torque_sensor_controller.h>
Public Member Functions | |
ForceTorqueSensorController () | |
virtual bool | init (hardware_interface::ForceTorqueSensorInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) |
virtual void | starting (const ros::Time &time) |
virtual void | stopping (const ros::Time &) |
virtual void | update (const ros::Time &time, const ros::Duration &) |
Private Types | |
typedef boost::shared_ptr < realtime_tools::RealtimePublisher < geometry_msgs::WrenchStamped > > | RtPublisherPtr |
Private Attributes | |
std::vector< ros::Time > | last_publish_times_ |
double | publish_rate_ |
std::vector< RtPublisherPtr > | realtime_pubs_ |
std::vector < hardware_interface::ForceTorqueSensorHandle > | sensors_ |
Definition at line 45 of file force_torque_sensor_controller.h.
typedef boost::shared_ptr<realtime_tools::RealtimePublisher<geometry_msgs::WrenchStamped> > force_torque_sensor_controller::ForceTorqueSensorController::RtPublisherPtr [private] |
Definition at line 57 of file force_torque_sensor_controller.h.
force_torque_sensor_controller::ForceTorqueSensorController::ForceTorqueSensorController | ( | ) | [inline] |
Definition at line 48 of file force_torque_sensor_controller.h.
bool force_torque_sensor_controller::ForceTorqueSensorController::init | ( | hardware_interface::ForceTorqueSensorInterface * | hw, |
ros::NodeHandle & | root_nh, | ||
ros::NodeHandle & | controller_nh | ||
) | [virtual] |
Reimplemented from controller_interface::Controller< hardware_interface::ForceTorqueSensorInterface >.
Definition at line 39 of file force_torque_sensor_controller.cpp.
void force_torque_sensor_controller::ForceTorqueSensorController::starting | ( | const ros::Time & | time | ) | [virtual] |
Reimplemented from controller_interface::ControllerBase.
Definition at line 66 of file force_torque_sensor_controller.cpp.
void force_torque_sensor_controller::ForceTorqueSensorController::stopping | ( | const ros::Time & | ) | [virtual] |
Reimplemented from controller_interface::ControllerBase.
Definition at line 101 of file force_torque_sensor_controller.cpp.
void force_torque_sensor_controller::ForceTorqueSensorController::update | ( | const ros::Time & | time, |
const ros::Duration & | |||
) | [virtual] |
Implements controller_interface::ControllerBase.
Definition at line 74 of file force_torque_sensor_controller.cpp.
std::vector<ros::Time> force_torque_sensor_controller::ForceTorqueSensorController::last_publish_times_ [private] |
Definition at line 59 of file force_torque_sensor_controller.h.
Definition at line 60 of file force_torque_sensor_controller.h.
std::vector<RtPublisherPtr> force_torque_sensor_controller::ForceTorqueSensorController::realtime_pubs_ [private] |
Definition at line 58 of file force_torque_sensor_controller.h.
std::vector<hardware_interface::ForceTorqueSensorHandle> force_torque_sensor_controller::ForceTorqueSensorController::sensors_ [private] |
Definition at line 56 of file force_torque_sensor_controller.h.