#include <cartesian_twist.h>
Definition at line 71 of file cartesian_twist.h.
◆ CartesianTwistController()
| robot_controllers::CartesianTwistController::CartesianTwistController |
( |
| ) |
|
◆ ~CartesianTwistController()
| virtual robot_controllers::CartesianTwistController::~CartesianTwistController |
( |
| ) |
|
|
inlinevirtual |
◆ command()
| void robot_controllers::CartesianTwistController::command |
( |
const geometry_msgs::TwistStamped::ConstPtr & |
goal | ) |
|
◆ getClaimedNames()
| std::vector< std::string > robot_controllers::CartesianTwistController::getClaimedNames |
( |
| ) |
|
|
virtual |
◆ getCommandedNames()
| std::vector< std::string > robot_controllers::CartesianTwistController::getCommandedNames |
( |
| ) |
|
|
virtual |
◆ getPose()
| KDL::Frame robot_controllers::CartesianTwistController::getPose |
( |
| ) |
|
|
private |
◆ getType()
| virtual std::string robot_controllers::CartesianTwistController::getType |
( |
| ) |
|
|
inlinevirtual |
◆ init()
Initialize the controller and any required data structures.
- Parameters
-
| nh | Node handle for this controller. |
| manager | The controller manager instance, this is needed for the controller to get information about joints, etc. |
- Returns
- 0 if succesfully configured, negative values are error codes.
Reimplemented from robot_controllers::Controller.
Definition at line 60 of file cartesian_twist.cpp.
◆ reset()
| bool robot_controllers::CartesianTwistController::reset |
( |
| ) |
|
|
virtual |
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves. This is mainly used in the case of the the robot exiting some fault condition.
- Returns
- True if successfully reset, false otherwise.
Implements robot_controllers::Controller.
Definition at line 158 of file cartesian_twist.cpp.
◆ start()
| bool robot_controllers::CartesianTwistController::start |
( |
| ) |
|
|
virtual |
◆ stop()
| bool robot_controllers::CartesianTwistController::stop |
( |
bool |
force | ) |
|
|
virtual |
Attempt to stop the controller. This should be called only by the ControllerManager instance.
- Parameters
-
| force | Should we force the controller to stop? Some controllers may wish to continue running until they absolutely have to stop. |
- Returns
- True if successfully stopped, false otherwise.
Implements robot_controllers::Controller.
Definition at line 152 of file cartesian_twist.cpp.
◆ update()
◆ command_sub_
◆ enabled_
| bool robot_controllers::CartesianTwistController::enabled_ |
|
private |
◆ feedback_pub_
| ros::Publisher robot_controllers::CartesianTwistController::feedback_pub_ |
|
private |
◆ fksolver_
◆ initialized_
| bool robot_controllers::CartesianTwistController::initialized_ |
|
private |
◆ is_active_
| bool robot_controllers::CartesianTwistController::is_active_ |
|
private |
◆ joints_
| std::vector<JointHandlePtr> robot_controllers::CartesianTwistController::joints_ |
|
private |
◆ kdl_chain_
| KDL::Chain robot_controllers::CartesianTwistController::kdl_chain_ |
|
private |
◆ last_command_time_
| ros::Time robot_controllers::CartesianTwistController::last_command_time_ |
|
private |
◆ last_tgt_jnt_vel_
| KDL::JntArray robot_controllers::CartesianTwistController::last_tgt_jnt_vel_ |
|
private |
◆ manager_
◆ mutex_
| boost::mutex robot_controllers::CartesianTwistController::mutex_ |
|
private |
◆ solver_
◆ tgt_jnt_pos_
| KDL::JntArray robot_controllers::CartesianTwistController::tgt_jnt_pos_ |
|
private |
◆ tgt_jnt_vel_
| KDL::JntArray robot_controllers::CartesianTwistController::tgt_jnt_vel_ |
|
private |
◆ twist_command_
| KDL::Twist robot_controllers::CartesianTwistController::twist_command_ |
|
private |
◆ twist_command_frame_
| std::string robot_controllers::CartesianTwistController::twist_command_frame_ |
|
private |
The documentation for this class was generated from the following files: