50 HeadPositionController::~HeadPositionController()
61 ROS_ERROR(
"HeadPositionController: No pan link name found on parameter server (namespace: %s)",
66 ROS_ERROR(
"HeadPositionController: No tilt link name found on parameter server (namespace: %s)",
110 if (command_msg->name.size() != 2 || command_msg->position.size() != 2){
111 ROS_ERROR(
"Head servoing controller expected joint command of size 2");
117 pan_out_ = command_msg->position[0];
123 pan_out_ = command_msg->position[1];
128 ROS_ERROR(
"Head servoing controller received invalid joint command");
std::string tilt_link_name_
PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::HeadPositionController, pr2_controller_interface::Controller) using namespace std
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
boost::shared_ptr< const urdf::Joint > joint_
pr2_mechanism_model::JointState * joint_state_
void command(const sensor_msgs::JointStateConstPtr &command_msg)
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
pr2_mechanism_model::RobotState * robot_state_
const std::string & getNamespace() const
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)
ros::Subscriber sub_command_
controller::JointPositionController head_pan_controller_
std::string pan_link_name_
controller::JointPositionController head_tilt_controller_
bool getParam(const std::string &key, std::string &s) const