#include <srh_example_controller.hpp>
Public Member Functions | |
bool | init (ros_ethercat_model::RobotState *robot, ros::NodeHandle &n) |
bool | init (ros_ethercat_model::RobotState *robot, const std::string &joint_name) |
SrhExampleController () | |
virtual void | starting (const ros::Time &time) |
virtual void | update (const ros::Time &time, const ros::Duration &period) |
virtual | ~SrhExampleController () |
Definition at line 35 of file srh_example_controller.hpp.
The controller manager will instanciate one instance of this class per controlled joint.
Definition at line 40 of file srh_example_controller.cpp.
controller::SrhExampleController::~SrhExampleController | ( | ) | [virtual] |
Destructor.
Definition at line 47 of file srh_example_controller.cpp.
bool controller::SrhExampleController::init | ( | ros_ethercat_model::RobotState * | robot, |
ros::NodeHandle & | n | ||
) | [virtual] |
The first init is used to read which joint is being controlled from the parameter server.
robot | A pointer to the robot state, passed to the 2nd init function. |
n | The ROS nodehandle, to be able to access the parameter server. |
Implements controller::SrController.
Definition at line 53 of file srh_example_controller.cpp.
bool controller::SrhExampleController::init | ( | ros_ethercat_model::RobotState * | robot, |
const std::string & | joint_name | ||
) |
This init funciton is called by the previous init function. It finishes to initalise the different necessary variables.
robot | A pointer to the robot state (used to get the joint_state) |
joint_name | The name of the joint which is controlled. |
Definition at line 78 of file srh_example_controller.cpp.
void controller::SrhExampleController::starting | ( | const ros::Time & | time | ) | [virtual] |
This method is called when the controller is started. The command is then to be the current position (or effort / velocity / ... depending on what you're controlling), so that the first command won't move the joint.
Reimplemented from controller::SrController.
Definition at line 131 of file srh_example_controller.cpp.
void controller::SrhExampleController::update | ( | const ros::Time & | time, |
const ros::Duration & | period | ||
) | [virtual] |
Issues commands to the joint. This method is called at the specified rate by the main loop.
Implements controller::SrController.
Definition at line 140 of file srh_example_controller.cpp.