53 CartesianWrenchController::CartesianWrenchController() :
73 nh.
param<std::string>(
"tip_name", tip_link,
"gripper_link");
77 if (!model.initParam(
"robot_description"))
87 ROS_ERROR(
"Could not construct tree from URDF");
94 ROS_ERROR(
"Could not construct chain from URDF");
123 "Unable to start, not initialized.");
130 "Unable to start, no goal.");
171 for (
unsigned int j = 0; j < 6; ++j)
176 for (
size_t j = 0; j <
joints_.size(); ++j)
182 for (
size_t i = 0; i <
joints_.size(); ++i)
202 ROS_ERROR(
"CartesianWrenchController: Cannot start, blocked by another controller.");
209 std::vector<std::string> names;
const Segment & getSegment(unsigned int nr) const
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
void resize(unsigned int newNrOfColumns)
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.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
unsigned int getNrOfSegments() const
virtual int requestStart(const std::string &name)
std::vector< JointHandlePtr > joints_
virtual int requestStop(const std::string &name)
const std::string & getName() const
KDL::Wrench desired_wrench_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void command(const geometry_msgs::Wrench::ConstPtr &goal)
Controller command.
const Joint & getJoint() const
unsigned int getNrOfJoints() const
boost::shared_ptr< KDL::ChainJntToJacSolver > jac_solver_
ros::Subscriber command_sub_
void resize(unsigned int newSize)
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
ControllerManager * manager_
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
#define ROS_ERROR_NAMED(name,...)
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
JointHandlePtr getJointHandle(const std::string &name)
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.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
const JointType & getType() const