A Cartesian ROS-controller for commanding target twists to a robot. More...
#include <twist_controller.h>

Public Member Functions | |
| virtual bool | init (TwistCommandInterface *hw, ros::NodeHandle &n) override |
| virtual void | starting (const ros::Time &time) override |
| TwistController ()=default | |
| virtual void | update (const ros::Time &, const ros::Duration &) override |
| virtual | ~TwistController ()=default |
Public Member Functions inherited from controller_interface::Controller< TwistCommandInterface > | |
| virtual bool | init (T *, ros::NodeHandle &) |
| virtual bool | init (T *, ros::NodeHandle &, ros::NodeHandle &) |
Public Member Functions inherited from controller_interface::ControllerBase | |
| virtual void | aborting (const ros::Time &) |
| virtual void | aborting (const ros::Time &) |
| bool | abortRequest (const ros::Time &time) |
| bool | abortRequest (const ros::Time &time) |
| ControllerBase ()=default | |
| ControllerBase (const ControllerBase &)=delete | |
| ControllerBase (ControllerBase &&)=delete | |
| bool | isAborted () const |
| bool | isAborted () const |
| bool | isInitialized () const |
| bool | isInitialized () const |
| bool | isRunning () const |
| bool | isRunning () const |
| bool | isStopped () const |
| bool | isStopped () const |
| bool | isWaiting () const |
| bool | isWaiting () const |
| ControllerBase & | operator= (const ControllerBase &)=delete |
| ControllerBase & | operator= (ControllerBase &&)=delete |
| bool | startRequest (const ros::Time &time) |
| bool | startRequest (const ros::Time &time) |
| virtual void | stopping (const ros::Time &) |
| virtual void | stopping (const ros::Time &) |
| bool | stopRequest (const ros::Time &time) |
| bool | stopRequest (const ros::Time &time) |
| void | updateRequest (const ros::Time &time, const ros::Duration &period) |
| void | updateRequest (const ros::Time &time, const ros::Duration &period) |
| virtual void | waiting (const ros::Time &) |
| virtual void | waiting (const ros::Time &) |
| bool | waitRequest (const ros::Time &time) |
| bool | waitRequest (const ros::Time &time) |
| virtual | ~ControllerBase ()=default |
Public Attributes | |
| realtime_tools::RealtimeBuffer< geometry_msgs::Twist > | command_buffer_ |
| TwistCommandHandle | handle_ |
Public Attributes inherited from controller_interface::ControllerBase | |
| ControllerState | state_ |
Private Member Functions | |
| void | reconfigureCallback (const twist_controller::TwistControllerConfig &config, uint32_t level) |
| void | twistCallback (const geometry_msgs::TwistConstPtr &msg) |
Private Attributes | |
| double | gain_ |
| std::shared_ptr< dynamic_reconfigure::Server< twist_controller::TwistControllerConfig > > | server_ |
| ros::Subscriber | twist_sub_ |
Additional Inherited Members | |
Public Types inherited from controller_interface::ControllerBase | |
| typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
| enum | ControllerState { ControllerState::CONSTRUCTED, ControllerState::INITIALIZED, ControllerState::RUNNING, ControllerState::STOPPED, ControllerState::WAITING, ControllerState::ABORTED } |
Protected Member Functions inherited from controller_interface::Controller< TwistCommandInterface > | |
| std::string | getHardwareInterfaceType () const |
| bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override |
A Cartesian ROS-controller for commanding target twists to a robot.
This controller makes use of a TwistCommandInterface to set a user specified twist message as reference for robot control. The according hardware_interface::RobotHW can send these commands directly to the robot driver in its write() function.
Definition at line 48 of file twist_controller.h.
|
default |
|
virtualdefault |
|
overridevirtual |
Definition at line 33 of file twist_controller.cpp.
|
private |
Definition at line 88 of file twist_controller.cpp.
|
overridevirtual |
Reimplemented from controller_interface::ControllerBase.
Definition at line 64 of file twist_controller.cpp.
|
private |
Definition at line 76 of file twist_controller.cpp.
|
inlineoverridevirtual |
Implements controller_interface::ControllerBase.
Definition at line 58 of file twist_controller.h.
| realtime_tools::RealtimeBuffer<geometry_msgs::Twist> ros_controllers_cartesian::TwistController::command_buffer_ |
Definition at line 64 of file twist_controller.h.
|
private |
Definition at line 70 of file twist_controller.h.
| TwistCommandHandle ros_controllers_cartesian::TwistController::handle_ |
Definition at line 63 of file twist_controller.h.
|
private |
Definition at line 71 of file twist_controller.h.
|
private |
Definition at line 67 of file twist_controller.h.