18 #ifndef COB_CARTESIAN_CONTROLLER_CARTESIAN_CONTROLLER_H    19 #define COB_CARTESIAN_CONTROLLER_CARTESIAN_CONTROLLER_H    23 #include <boost/shared_ptr.hpp>    31 #include <cob_cartesian_controller/CartesianControllerAction.h>    39 #define DEFAULT_CARTESIAN_TARGET "cartesian_target"    57     void actionPreempt(
const bool success, 
const std::string& message);
    58     void actionAbort(
const bool success, 
const std::string& message);
    86 #endif  // COB_CARTESIAN_CONTROLLER_CARTESIAN_CONTROLLER_H boost::shared_ptr< TrajectoryInterpolator > trajectory_interpolator_
ros::ServiceClient start_tracking_
std::string action_name_
Action interface. 
cob_cartesian_controller::CartesianActionStruct acceptGoal(boost::shared_ptr< const cob_cartesian_controller::CartesianControllerGoal > goal)
actionlib::SimpleActionServer< cob_cartesian_controller::CartesianControllerAction > SAS_CartesianControllerAction_t
void actionPreempt(const bool success, const std::string &message)
cob_cartesian_controller::MoveLinStruct convertMoveLin(const cob_cartesian_controller::MoveLin &move_lin_msg)
CartesianControllerUtils utils_
std::string chain_tip_link_
tf::TransformBroadcaster tf_broadcaster_
cob_cartesian_controller::CartesianControllerFeedback action_feedback_
bool posePathBroadcaster(const geometry_msgs::PoseArray &cartesian_path)
ros::ServiceClient stop_tracking_
boost::shared_ptr< SAS_CartesianControllerAction_t > as_
void goalCallback()
Action interface. 
cob_cartesian_controller::CartesianControllerResult action_result_
tf::TransformListener tf_listener_
cob_cartesian_controller::MoveCircStruct convertMoveCirc(const cob_cartesian_controller::MoveCirc &move_circ_msg)
void actionSuccess(const bool success, const std::string &message)
std::string target_frame_
void actionAbort(const bool success, const std::string &message)