42 #ifndef ROBOT_CONTROLLERS_CARTESIAN_WRENCH_H 43 #define ROBOT_CONTROLLERS_CARTESIAN_WRENCH_H 47 #include <boost/shared_ptr.hpp> 53 #include <geometry_msgs/Wrench.h> 55 #include <kdl/chain.hpp> 56 #include <kdl/chainjnttojacsolver.hpp> 57 #include <kdl/frames.hpp> 94 virtual bool stop(
bool force);
102 virtual bool reset();
114 return "robot_controllers/CartesianWrenchController";
124 void command(
const geometry_msgs::Wrench::ConstPtr&
goal);
153 #endif // ROBOT_CONTROLLERS_CARTESIAN_WRENCH_H
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
tf::TransformListener tf_
CartesianWrenchController()
virtual std::string getType()
Get the type of this controller.
std::vector< JointHandlePtr > joints_
virtual ~CartesianWrenchController()
KDL::Wrench desired_wrench_
void command(const geometry_msgs::Wrench::ConstPtr &goal)
Controller command.
boost::shared_ptr< KDL::ChainJntToJacSolver > jac_solver_
ros::Publisher feedback_pub_
ros::Subscriber command_sub_
ControllerManager * manager_
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
virtual bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
virtual bool reset()
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves...
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.