55 CartesianPoseController::CartesianPoseController() :
75 nh.
param<std::string>(
"tip_name", tip_link,
"gripper_link");
79 if (!model.initParam(
"robot_description"))
89 ROS_ERROR(
"Could not construct tree from URDF");
96 ROS_ERROR(
"Could not construct chain from URDF");
109 for (
unsigned int i = 0; i < 3; i++)
110 pid_.push_back(pid_controller);
112 for (
unsigned int i = 0; i < 3; i++)
113 pid_.push_back(pid_controller);
138 "Unable to start, not initialized.");
145 "Unable to start, no goal.");
175 geometry_msgs::Twist t;
185 for (
size_t i = 0; i < 6; ++i)
195 for (
unsigned int j = 0; j < 6; ++j)
200 for (
size_t j = 0; j <
joints_.size(); ++j)
206 for (
size_t i = 0; i <
joints_.size(); ++i)
220 ROS_ERROR(
"CartesianPoseController: Cannot accept goal, controller is not initialized.");
238 ROS_ERROR(
"CartesianPoseController: Cannot start, blocked by another controller.");
251 std::vector<std::string> names;
IMETHOD doubleVel diff(const doubleVel &a, const doubleVel &b, double dt=1.0)
const Segment & getSegment(unsigned int nr) const
void publish(const boost::shared_ptr< M > &message) const
std::vector< JointHandlePtr > joints_
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
void resize(unsigned int newNrOfColumns)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ControllerManager * manager_
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
unsigned int getNrOfSegments() const
ros::Publisher feedback_pub_
virtual bool reset()
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves...
virtual int requestStart(const std::string &name)
tf::TransformListener tf_
void poseTFToKDL(const tf::Pose &t, KDL::Frame &k)
virtual int requestStop(const std::string &name)
const std::string & getName() const
void command(const geometry_msgs::PoseStamped::ConstPtr &goal)
Controller command.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
boost::shared_ptr< KDL::ChainJntToJacSolver > jac_solver_
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
const Joint & getJoint() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
unsigned int getNrOfJoints() const
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.
virtual bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
void resize(unsigned int newSize)
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
std::vector< robot_controllers::PID > pid_
boost::shared_ptr< KDL::ChainFkSolverPos > jnt_to_pose_solver_
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
ros::Subscriber command_sub_
#define ROS_ERROR_NAMED(name,...)
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.
static void poseStampedMsgToTF(const geometry_msgs::PoseStamped &msg, Stamped< Pose > &bt)
JointHandlePtr getJointHandle(const std::string &name)
#define ROS_ERROR_STREAM(args)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool init(const ros::NodeHandle &nh)
initialize gain settings from ROS parameter values
const JointType & getType() const