42 #ifndef ROBOT_CONTROLLERS_CARTESIAN_TWIST_H 43 #define ROBOT_CONTROLLERS_CARTESIAN_TWIST_H 47 #include <boost/shared_ptr.hpp> 54 #include <geometry_msgs/PoseStamped.h> 55 #include <geometry_msgs/TwistStamped.h> 57 #include <kdl/chain.hpp> 58 #include <kdl/chainiksolvervel_wdls.hpp> 59 #include <kdl/chainfksolver.hpp> 60 #include <kdl/chainfksolverpos_recursive.hpp> 61 #include <kdl/frames.hpp> 100 virtual bool stop(
bool force);
108 virtual bool reset();
120 return "robot_controllers/CartesianTwistController";
130 void command(
const geometry_msgs::TwistStamped::ConstPtr&
goal);
161 #endif // ROBOT_CONTROLLERS_CARTESIAN_TWIST_H boost::shared_ptr< KDL::ChainIkSolverVel_wdls > solver_
KDL::JntArray last_tgt_jnt_vel_
KDL::JntArray tgt_jnt_vel_
ros::Time last_command_time_
ros::Publisher feedback_pub_
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
void command(const geometry_msgs::TwistStamped::ConstPtr &goal)
Controller command.
ros::Subscriber command_sub_
boost::shared_ptr< KDL::ChainFkSolverPos_recursive > fksolver_
CartesianTwistController()
virtual std::string getType()
Get the type of this controller.
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.
ControllerManager * manager_
virtual bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
KDL::JntArray tgt_jnt_pos_
virtual bool reset()
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves...
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
virtual ~CartesianTwistController()
std::vector< JointHandlePtr > joints_
KDL::Twist twist_command_
std::string twist_command_frame_