Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include "joint_qualification_controllers/head_position_controller.h"
00037 #include "pluginlib/class_list_macros.h"
00038
00039
00040
00041 PLUGINLIB_DECLARE_CLASS(joint_qualification_controllers, HeadPositionController,
00042 joint_qualification_controllers::HeadPositionController,
00043 pr2_controller_interface::Controller)
00044
00045 using namespace std;
00046 using namespace joint_qualification_controllers;
00047
00048 HeadPositionController::HeadPositionController()
00049 : robot_state_(NULL)
00050 {}
00051
00052 HeadPositionController::~HeadPositionController()
00053 {
00054 sub_command_.shutdown();
00055 }
00056
00057 bool HeadPositionController::init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &n)
00058 {
00059 node_ = n;
00060
00061
00062 if (!node_.getParam("pan_link_name", pan_link_name_)){
00063 ROS_ERROR("HeadPositionController: No pan link name found on parameter server (namespace: %s)",
00064 node_.getNamespace().c_str());
00065 return false;
00066 }
00067 if (!node_.getParam("tilt_link_name", tilt_link_name_)){
00068 ROS_ERROR("HeadPositionController: No tilt link name found on parameter server (namespace: %s)",
00069 node_.getNamespace().c_str());
00070 return false;
00071 }
00072
00073
00074 assert(robot_state);
00075 robot_state_ = robot_state;
00076
00077
00078
00079 ros::NodeHandle nh_pan(node_, "pan_controller");
00080 ros::NodeHandle nh_tilt(node_, "tilt_controller");
00081 head_pan_controller_.init(robot_state, nh_pan);
00082 head_tilt_controller_.init(robot_state, nh_tilt);
00083
00084
00085
00086 sub_command_ = node_.subscribe<sensor_msgs::JointState>("command", 1, &HeadPositionController::command, this);
00087
00088 return true;
00089 }
00090
00091 void HeadPositionController::starting()
00092 {
00093 pan_out_ = head_pan_controller_.joint_state_->position_;
00094 tilt_out_ = head_tilt_controller_.joint_state_->position_;
00095 head_pan_controller_.starting();
00096 head_tilt_controller_.starting();
00097 }
00098
00099 void HeadPositionController::update()
00100 {
00101
00102 head_pan_controller_.command_ = pan_out_;
00103 head_tilt_controller_.command_ = tilt_out_;
00104 head_pan_controller_.update();
00105 head_tilt_controller_.update();
00106 }
00107
00108 void HeadPositionController::command(const sensor_msgs::JointStateConstPtr& command_msg)
00109 {
00110
00111
00112 if (command_msg->name.size() != 2 || command_msg->position.size() != 2){
00113 ROS_ERROR("Head servoing controller expected joint command of size 2");
00114 return;
00115 }
00116 if (command_msg->name[0] == head_pan_controller_.joint_state_->joint_->name &&
00117 command_msg->name[1] == head_tilt_controller_.joint_state_->joint_->name)
00118 {
00119 pan_out_ = command_msg->position[0];
00120 tilt_out_ = command_msg->position[1];
00121 }
00122 else if (command_msg->name[1] == head_pan_controller_.joint_state_->joint_->name &&
00123 command_msg->name[0] == head_tilt_controller_.joint_state_->joint_->name)
00124 {
00125 pan_out_ = command_msg->position[1];
00126 tilt_out_ = command_msg->position[0];
00127 }
00128 else
00129 {
00130 ROS_ERROR("Head servoing controller received invalid joint command");
00131 }
00132 }
00133
00134
00135