45 Pr2GripperController::Pr2GripperController()
47 loop_count_(0), robot_(NULL), last_time_(0)
62 std::string joint_name;
69 ROS_ERROR(
"Could not find joint named \"%s\" (namespace: %s)",
75 ROS_ERROR(
"The joint \"%s\" was not prismatic (namespace: %s)",
82 ROS_ERROR(
"Joint %s is not calibrated (namespace: %s)",
111 pr2_controllers_msgs::Pr2GripperCommandConstPtr
command;
120 if (command->max_effort >= 0.0)
122 effort = std::max(-command->max_effort, std::min(effort, command->max_effort));
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
void commandCB(const pr2_controllers_msgs::Pr2GripperCommandConstPtr &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
realtime_tools::RealtimeBox< pr2_controllers_msgs::Pr2GripperCommandConstPtr > command_box_
ros::Subscriber sub_command_
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
virtual void update()
Issues commands to the joint. Should be called at regular intervals.
boost::shared_ptr< const urdf::Joint > joint_
pr2_mechanism_model::RobotState * robot_
ROSLIB_DECL std::string command(const std::string &cmd)
const std::string & getNamespace() const
control_toolbox::Pid pid_
JointState * getJointState(const std::string &name)
bool getParam(const std::string &key, std::string &s) const
pr2_mechanism_model::JointState * joint_state_
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerState > > controller_state_publisher_