Public Member Functions | Private Attributes
CartesianController Class Reference

#include <cartesian_controller.h>

List of all members.

Public Member Functions

cob_cartesian_controller::CartesianActionStruct acceptGoal (boost::shared_ptr< const cob_cartesian_controller::CartesianControllerGoal > goal)
void actionAbort (const bool success, const std::string &message)
void actionPreempt (const bool success, const std::string &message)
void actionSuccess (const bool success, const std::string &message)
cob_cartesian_controller::MoveCircStruct convertMoveCirc (const cob_cartesian_controller::MoveCirc &move_circ_msg)
cob_cartesian_controller::MoveLinStruct convertMoveLin (const cob_cartesian_controller::MoveLin &move_lin_msg)
void goalCallback ()
 Action interface.
bool initialize ()
bool posePathBroadcaster (const geometry_msgs::PoseArray &cartesian_path)
void preemptCallback ()
bool startTracking ()
bool stopTracking ()

Private Attributes

cob_cartesian_controller::CartesianControllerFeedback action_feedback_
std::string action_name_
 Action interface.
cob_cartesian_controller::CartesianControllerResult action_result_
boost::shared_ptr
< SAS_CartesianControllerAction_t
as_
std::string chain_tip_link_
ros::NodeHandle nh_
std::string root_frame_
ros::ServiceClient start_tracking_
ros::ServiceClient stop_tracking_
std::string target_frame_
tf::TransformBroadcaster tf_broadcaster_
tf::TransformListener tf_listener_
bool tracking_
boost::shared_ptr
< TrajectoryInterpolator
trajectory_interpolator_
double update_rate_
CartesianControllerUtils utils_

Detailed Description

Definition at line 41 of file cartesian_controller.h.


Member Function Documentation

cob_cartesian_controller::CartesianActionStruct CartesianController::acceptGoal ( boost::shared_ptr< const cob_cartesian_controller::CartesianControllerGoal >  goal)

Definition at line 290 of file cartesian_controller.cpp.

void CartesianController::actionAbort ( const bool  success,
const std::string &  message 
)

Definition at line 340 of file cartesian_controller.cpp.

void CartesianController::actionPreempt ( const bool  success,
const std::string &  message 
)

Definition at line 332 of file cartesian_controller.cpp.

void CartesianController::actionSuccess ( const bool  success,
const std::string &  message 
)

Definition at line 324 of file cartesian_controller.cpp.

cob_cartesian_controller::MoveCircStruct CartesianController::convertMoveCirc ( const cob_cartesian_controller::MoveCirc &  move_circ_msg)

Definition at line 275 of file cartesian_controller.cpp.

cob_cartesian_controller::MoveLinStruct CartesianController::convertMoveLin ( const cob_cartesian_controller::MoveLin &  move_lin_msg)

Definition at line 261 of file cartesian_controller.cpp.

Action interface.

Definition at line 173 of file cartesian_controller.cpp.

Private Nodehandle

Definition at line 29 of file cartesian_controller.cpp.

bool CartesianController::posePathBroadcaster ( const geometry_msgs::PoseArray &  cartesian_path)

Definition at line 140 of file cartesian_controller.cpp.

Definition at line 317 of file cartesian_controller.cpp.

Definition at line 77 of file cartesian_controller.cpp.

Definition at line 113 of file cartesian_controller.cpp.


Member Data Documentation

cob_cartesian_controller::CartesianControllerFeedback CartesianController::action_feedback_ [private]

Definition at line 79 of file cartesian_controller.h.

std::string CartesianController::action_name_ [private]

Action interface.

Definition at line 77 of file cartesian_controller.h.

cob_cartesian_controller::CartesianControllerResult CartesianController::action_result_ [private]

Definition at line 80 of file cartesian_controller.h.

Definition at line 78 of file cartesian_controller.h.

std::string CartesianController::chain_tip_link_ [private]

Definition at line 74 of file cartesian_controller.h.

Definition at line 65 of file cartesian_controller.h.

std::string CartesianController::root_frame_ [private]

Definition at line 74 of file cartesian_controller.h.

Definition at line 69 of file cartesian_controller.h.

Definition at line 70 of file cartesian_controller.h.

std::string CartesianController::target_frame_ [private]

Definition at line 74 of file cartesian_controller.h.

Definition at line 67 of file cartesian_controller.h.

Definition at line 66 of file cartesian_controller.h.

Definition at line 71 of file cartesian_controller.h.

Definition at line 83 of file cartesian_controller.h.

Definition at line 73 of file cartesian_controller.h.

Definition at line 82 of file cartesian_controller.h.


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


cob_cartesian_controller
Author(s): Christoph Mark
autogenerated on Thu Jun 6 2019 21:19:40