Class ControllerManager
Defined in File controller_manager.h
Inheritance Relationships
Base Type
public std::enable_shared_from_this< ControllerManager >
Class Documentation
-
class ControllerManager : public std::enable_shared_from_this<ControllerManager>
Base class for a controller manager.
Public Functions
-
ControllerManager()
-
inline virtual ~ControllerManager()
Ensure proper shutdown with virtual destructor.
Startup the controller manager, loading default controllers.
Note: JointHandles should be added before this is called.
- Parameters:
nh – The proper node handle for finding parameters.
- Returns:
0 if success, negative values are error codes.
Older interface that does not allow for passing in a buffer.
-
virtual int requestStart(const std::string &name)
Start a controller.
-
virtual int requestStop(const std::string &name)
Stop a controller.
-
virtual void update(const rclcpp::Time &time, const rclcpp::Duration &dt)
Update active controllers.
-
virtual void reset()
Reset all controllers.
-
bool addJointHandle(JointHandlePtr &joint_handle_ptr)
Add a joint handle.
-
bool addGyroHandle(GyroHandlePtr gyro_hanle_ptr)
Add a gyro handle.
-
HandlePtr getHandle(const std::string &name)
Get the handle associated with a particular joint/controller name.
- Parameters:
name – The name of the joint/controller.
-
JointHandlePtr getJointHandle(const std::string &name)
Get the joint handle associated with a particular joint name.
This is mainly a convienence function.
- Parameters:
name – The name of the joint.
-
GyroHandlePtr getGyroHandle(const std::string &name)
Get the gyro handle associated with a particular gyro name.
This is mainly a convienence function.
- Parameters:
name – The name of the gyro.
-
std::vector<std::string> getJointNames()
Get the names of all joints.
-
std::vector<std::string> getControllerNames()
Get the names of all controllers.
-
std::shared_ptr<tf2_ros::Buffer> getTransformBuffer()
In ROS2, each transform listener incurs an extra node, limit this reusing the same transform listener where possible.
-
ControllerManager()