Public Member Functions | Private Member Functions | Private Attributes | List of all members
robot_controllers::CartesianPoseController Class Reference

#include <cartesian_pose.h>

Inheritance diagram for robot_controllers::CartesianPoseController:
Inheritance graph
[legend]

Public Member Functions

 CartesianPoseController ()
 
void command (const geometry_msgs::PoseStamped::ConstPtr &goal)
 Controller command. More...
 
virtual std::vector< std::string > getClaimedNames ()
 Get the names of joints/controllers which this controller exclusively claims. More...
 
virtual std::vector< std::string > getCommandedNames ()
 Get the names of joints/controllers which this controller commands. More...
 
virtual std::string getType ()
 Get the type of this controller. More...
 
virtual int init (ros::NodeHandle &nh, ControllerManager *manager)
 Initialize the controller and any required data structures. More...
 
virtual bool reset ()
 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. More...
 
virtual bool start ()
 Attempt to start the controller. This should be called only by the ControllerManager instance. More...
 
virtual bool stop (bool force)
 Attempt to stop the controller. This should be called only by the ControllerManager instance. More...
 
virtual void update (const ros::Time &now, const ros::Duration &dt)
 This is the update loop for the controller. More...
 
virtual ~CartesianPoseController ()
 
- Public Member Functions inherited from robot_controllers::Controller
 Controller ()
 
std::string getName ()
 
virtual ~Controller ()
 
- Public Member Functions inherited from robot_controllers::Handle
 Handle ()
 
virtual ~Handle ()
 

Private Member Functions

KDL::Frame getPose ()
 

Private Attributes

KDL::Frame actual_pose_
 
ros::Subscriber command_sub_
 
KDL::Frame desired_pose_
 
bool enabled_
 
ros::Publisher feedback_pub_
 
bool initialized_
 
boost::shared_ptr< KDL::ChainJntToJacSolverjac_solver_
 
KDL::Jacobian jacobian_
 
KDL::JntArray jnt_delta_
 
KDL::JntArray jnt_pos_
 
boost::shared_ptr< KDL::ChainFkSolverPosjnt_to_pose_solver_
 
std::vector< JointHandlePtrjoints_
 
KDL::Chain kdl_chain_
 
ros::Time last_command_
 
ControllerManagermanager_
 
std::vector< robot_controllers::PIDpid_
 
std::string root_link_
 
tf::TransformListener tf_
 
KDL::Twist twist_error_
 

Detailed Description

Definition at line 69 of file cartesian_pose.h.

Constructor & Destructor Documentation

robot_controllers::CartesianPoseController::CartesianPoseController ( )

Definition at line 55 of file cartesian_pose.cpp.

virtual robot_controllers::CartesianPoseController::~CartesianPoseController ( )
inlinevirtual

Definition at line 73 of file cartesian_pose.h.

Member Function Documentation

void robot_controllers::CartesianPoseController::command ( const geometry_msgs::PoseStamped::ConstPtr &  goal)

Controller command.

Definition at line 215 of file cartesian_pose.cpp.

std::vector< std::string > robot_controllers::CartesianPoseController::getClaimedNames ( )
virtual

Get the names of joints/controllers which this controller exclusively claims.

Implements robot_controllers::Controller.

Definition at line 261 of file cartesian_pose.cpp.

std::vector< std::string > robot_controllers::CartesianPoseController::getCommandedNames ( )
virtual

Get the names of joints/controllers which this controller commands.

Implements robot_controllers::Controller.

Definition at line 249 of file cartesian_pose.cpp.

KDL::Frame robot_controllers::CartesianPoseController::getPose ( )
private

Definition at line 204 of file cartesian_pose.cpp.

virtual std::string robot_controllers::CartesianPoseController::getType ( )
inlinevirtual

Get the type of this controller.

Reimplemented from robot_controllers::Controller.

Definition at line 116 of file cartesian_pose.h.

int robot_controllers::CartesianPoseController::init ( ros::NodeHandle nh,
ControllerManager manager 
)
virtual

Initialize the controller and any required data structures.

Parameters
nhNode handle for this controller.
managerThe 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_pose.cpp.

bool robot_controllers::CartesianPoseController::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_pose.cpp.

bool robot_controllers::CartesianPoseController::start ( )
virtual

Attempt to start the controller. This should be called only by the ControllerManager instance.

Returns
True if successfully started, false otherwise.

Implements robot_controllers::Controller.

Definition at line 133 of file cartesian_pose.cpp.

bool robot_controllers::CartesianPoseController::stop ( bool  force)
virtual

Attempt to stop the controller. This should be called only by the ControllerManager instance.

Parameters
forceShould 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_pose.cpp.

void robot_controllers::CartesianPoseController::update ( const ros::Time now,
const ros::Duration dt 
)
virtual

This is the update loop for the controller.

Parameters
timeThe system time.
dtThe timestep since last call to update.

Implements robot_controllers::Controller.

Definition at line 164 of file cartesian_pose.cpp.

Member Data Documentation

KDL::Frame robot_controllers::CartesianPoseController::actual_pose_
private

Definition at line 141 of file cartesian_pose.h.

ros::Subscriber robot_controllers::CartesianPoseController::command_sub_
private

Definition at line 153 of file cartesian_pose.h.

KDL::Frame robot_controllers::CartesianPoseController::desired_pose_
private

Definition at line 140 of file cartesian_pose.h.

bool robot_controllers::CartesianPoseController::enabled_
private

Definition at line 136 of file cartesian_pose.h.

ros::Publisher robot_controllers::CartesianPoseController::feedback_pub_
private

Definition at line 152 of file cartesian_pose.h.

bool robot_controllers::CartesianPoseController::initialized_
private

Definition at line 133 of file cartesian_pose.h.

boost::shared_ptr<KDL::ChainJntToJacSolver> robot_controllers::CartesianPoseController::jac_solver_
private

Definition at line 147 of file cartesian_pose.h.

KDL::Jacobian robot_controllers::CartesianPoseController::jacobian_
private

Definition at line 150 of file cartesian_pose.h.

KDL::JntArray robot_controllers::CartesianPoseController::jnt_delta_
private

Definition at line 149 of file cartesian_pose.h.

KDL::JntArray robot_controllers::CartesianPoseController::jnt_pos_
private

Definition at line 148 of file cartesian_pose.h.

boost::shared_ptr<KDL::ChainFkSolverPos> robot_controllers::CartesianPoseController::jnt_to_pose_solver_
private

Definition at line 146 of file cartesian_pose.h.

std::vector<JointHandlePtr> robot_controllers::CartesianPoseController::joints_
private

Definition at line 156 of file cartesian_pose.h.

KDL::Chain robot_controllers::CartesianPoseController::kdl_chain_
private

Definition at line 145 of file cartesian_pose.h.

ros::Time robot_controllers::CartesianPoseController::last_command_
private

Definition at line 138 of file cartesian_pose.h.

ControllerManager* robot_controllers::CartesianPoseController::manager_
private

Definition at line 134 of file cartesian_pose.h.

std::vector<robot_controllers::PID> robot_controllers::CartesianPoseController::pid_
private

Definition at line 157 of file cartesian_pose.h.

std::string robot_controllers::CartesianPoseController::root_link_
private

Definition at line 137 of file cartesian_pose.h.

tf::TransformListener robot_controllers::CartesianPoseController::tf_
private

Definition at line 155 of file cartesian_pose.h.

KDL::Twist robot_controllers::CartesianPoseController::twist_error_
private

Definition at line 143 of file cartesian_pose.h.


The documentation for this class was generated from the following files:


robot_controllers
Author(s): Michael Ferguson
autogenerated on Sun Sep 27 2020 03:22:39