#include <cartesian_wrench.h>
Definition at line 65 of file cartesian_wrench.h.
◆ CartesianWrenchController()
robot_controllers::CartesianWrenchController::CartesianWrenchController |
( |
| ) |
|
◆ ~CartesianWrenchController()
virtual robot_controllers::CartesianWrenchController::~CartesianWrenchController |
( |
| ) |
|
|
inlinevirtual |
◆ command()
void robot_controllers::CartesianWrenchController::command |
( |
const geometry_msgs::Wrench::ConstPtr & |
goal | ) |
|
◆ getClaimedNames()
std::vector< std::string > robot_controllers::CartesianWrenchController::getClaimedNames |
( |
| ) |
|
|
virtual |
◆ getCommandedNames()
std::vector< std::string > robot_controllers::CartesianWrenchController::getCommandedNames |
( |
| ) |
|
|
virtual |
◆ getType()
virtual std::string robot_controllers::CartesianWrenchController::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 58 of file cartesian_wrench.cpp.
◆ reset()
bool robot_controllers::CartesianWrenchController::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 142 of file cartesian_wrench.cpp.
◆ start()
bool robot_controllers::CartesianWrenchController::start |
( |
| ) |
|
|
virtual |
◆ stop()
bool robot_controllers::CartesianWrenchController::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 137 of file cartesian_wrench.cpp.
◆ update()
◆ updateJoints()
void robot_controllers::CartesianWrenchController::updateJoints |
( |
| ) |
|
|
private |
◆ command_sub_
◆ desired_wrench_
KDL::Wrench robot_controllers::CartesianWrenchController::desired_wrench_ |
|
private |
◆ enabled_
bool robot_controllers::CartesianWrenchController::enabled_ |
|
private |
◆ feedback_pub_
ros::Publisher robot_controllers::CartesianWrenchController::feedback_pub_ |
|
private |
◆ initialized_
bool robot_controllers::CartesianWrenchController::initialized_ |
|
private |
◆ jac_solver_
◆ jacobian_
KDL::Jacobian robot_controllers::CartesianWrenchController::jacobian_ |
|
private |
◆ jnt_eff_
KDL::JntArray robot_controllers::CartesianWrenchController::jnt_eff_ |
|
private |
◆ jnt_pos_
KDL::JntArray robot_controllers::CartesianWrenchController::jnt_pos_ |
|
private |
◆ joints_
std::vector<JointHandlePtr> robot_controllers::CartesianWrenchController::joints_ |
|
private |
◆ kdl_chain_
KDL::Chain robot_controllers::CartesianWrenchController::kdl_chain_ |
|
private |
◆ last_command_
ros::Time robot_controllers::CartesianWrenchController::last_command_ |
|
private |
◆ manager_
◆ root_link_
std::string robot_controllers::CartesianWrenchController::root_link_ |
|
private |
◆ tf_
The documentation for this class was generated from the following files: