$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 #include <cmath> 00036 00037 #include <ros/ros.h> 00038 #include <actionlib/server/action_server.h> 00039 00040 #include <trajectory_msgs/JointTrajectory.h> 00041 #include <pr2_controllers_msgs/SingleJointPositionAction.h> 00042 #include <pr2_controllers_msgs/QueryTrajectoryState.h> 00043 #include <pr2_controllers_msgs/JointTrajectoryControllerState.h> 00044 00045 class SingleJointPositionNode 00046 { 00047 private: 00048 typedef actionlib::ActionServer<pr2_controllers_msgs::SingleJointPositionAction> SJPAS; 00049 typedef SJPAS::GoalHandle GoalHandle; 00050 public: 00051 SingleJointPositionNode(const ros::NodeHandle &n) 00052 : node_(n), 00053 action_server_(node_, "position_joint_action", 00054 boost::bind(&SingleJointPositionNode::goalCB, this, _1), 00055 boost::bind(&SingleJointPositionNode::cancelCB, this, _1)), 00056 has_active_goal_(false) 00057 { 00058 ros::NodeHandle pn("~"); 00059 if (!pn.getParam("joint", joint_)) 00060 { 00061 ROS_FATAL("No joint given."); 00062 exit(1); 00063 } 00064 00065 pn.param("goal_threshold", goal_threshold_, 0.1); 00066 pn.param("max_acceleration", max_accel_, -1.0); 00067 00068 // Connects to the controller 00069 pub_controller_command_ = 00070 node_.advertise<trajectory_msgs::JointTrajectory>("command", 2); 00071 sub_controller_state_ = 00072 node_.subscribe("state", 1, &SingleJointPositionNode::controllerStateCB, this); 00073 cli_query_traj_ = 00074 node_.serviceClient<pr2_controllers_msgs::QueryTrajectoryState>("query_state"); 00075 00076 watchdog_timer_ = node_.createTimer(ros::Duration(1.0), &SingleJointPositionNode::watchdog, this); 00077 } 00078 00079 00080 //void pointHeadCB(const geometry_msgs::PointStampedConstPtr &msg) 00081 void goalCB(GoalHandle gh) 00082 { 00083 // Queries where the movement should start. 00084 pr2_controllers_msgs::QueryTrajectoryState traj_state; 00085 traj_state.request.time = ros::Time::now() + ros::Duration(0.01); 00086 if (!cli_query_traj_.call(traj_state)) 00087 { 00088 ROS_ERROR("Service call to query controller trajectory failed. Service: (%s)", 00089 cli_query_traj_.getService().c_str()); 00090 gh.setRejected(); 00091 return; 00092 } 00093 00094 if (has_active_goal_) 00095 { 00096 active_goal_.setCanceled(); 00097 has_active_goal_ = false; 00098 } 00099 00100 gh.setAccepted(); 00101 active_goal_ = gh; 00102 has_active_goal_ = true; 00103 00104 // Computes the duration of the movement. 00105 00106 ros::Duration min_duration(0.01); 00107 00108 if (gh.getGoal()->min_duration > min_duration) 00109 min_duration = gh.getGoal()->min_duration; 00110 00111 // Determines if we need to increase the duration of the movement 00112 // in order to enforce a maximum velocity. 00113 if (gh.getGoal()->max_velocity > 0) 00114 { 00115 // Very approximate velocity limiting. 00116 double dist = fabs(gh.getGoal()->position - traj_state.response.position[0]); 00117 ros::Duration limit_from_velocity(dist / gh.getGoal()->max_velocity); 00119 if (limit_from_velocity > min_duration) 00120 min_duration = limit_from_velocity; 00121 } 00122 00123 // Computes the command to send to the trajectory controller. 00124 trajectory_msgs::JointTrajectory traj; 00125 traj.header.stamp = traj_state.request.time; 00126 00127 traj.joint_names.push_back(joint_); 00128 00129 traj.points.resize(2); 00130 traj.points[0].positions = traj_state.response.position; 00131 traj.points[0].velocities = traj_state.response.velocity; 00132 traj.points[0].time_from_start = ros::Duration(0.0); 00133 traj.points[1].positions.push_back(gh.getGoal()->position); 00134 traj.points[1].velocities.push_back(0); 00135 traj.points[1].time_from_start = ros::Duration(min_duration); 00136 00137 pub_controller_command_.publish(traj); 00138 } 00139 00140 00141 private: 00142 std::string joint_; 00143 double max_accel_; 00144 double goal_threshold_; 00145 00146 ros::NodeHandle node_; 00147 ros::Publisher pub_controller_command_; 00148 ros::Subscriber sub_controller_state_; 00149 ros::Subscriber command_sub_; 00150 ros::ServiceClient cli_query_traj_; 00151 ros::Timer watchdog_timer_; 00152 00153 SJPAS action_server_; 00154 bool has_active_goal_; 00155 GoalHandle active_goal_; 00156 00157 void watchdog(const ros::TimerEvent &e) 00158 { 00159 ros::Time now = ros::Time::now(); 00160 00161 // Aborts the active goal if the controller does not appear to be active. 00162 if (has_active_goal_) 00163 { 00164 bool should_abort = false; 00165 if (!last_controller_state_) 00166 { 00167 should_abort = true; 00168 ROS_WARN("Aborting goal because we have never heard a controller state message."); 00169 } 00170 else if ((now - last_controller_state_->header.stamp) > ros::Duration(5.0)) 00171 { 00172 should_abort = true; 00173 ROS_WARN("Aborting goal because we haven't heard from the controller in %.3lf seconds", 00174 (now - last_controller_state_->header.stamp).toSec()); 00175 } 00176 00177 if (should_abort) 00178 { 00179 // Stops the controller. 00180 trajectory_msgs::JointTrajectory empty; 00181 empty.joint_names.push_back(joint_); 00182 pub_controller_command_.publish(empty); 00183 00184 // Marks the current goal as aborted. 00185 active_goal_.setAborted(); 00186 has_active_goal_ = false; 00187 } 00188 } 00189 } 00190 00191 void cancelCB(GoalHandle gh) 00192 { 00193 if (active_goal_ == gh) 00194 { 00195 // Stops the controller. 00196 trajectory_msgs::JointTrajectory empty; 00197 empty.joint_names.push_back(joint_); 00198 pub_controller_command_.publish(empty); 00199 00200 // Marks the current goal as canceled. 00201 active_goal_.setCanceled(); 00202 has_active_goal_ = false; 00203 } 00204 } 00205 00206 pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr last_controller_state_; 00207 void controllerStateCB(const pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr &msg) 00208 { 00209 last_controller_state_ = msg; 00210 ros::Time now = ros::Time::now(); 00211 00212 if (!has_active_goal_) 00213 return; 00214 00215 pr2_controllers_msgs::SingleJointPositionFeedback feedback; 00216 feedback.header.stamp = msg->header.stamp; 00217 feedback.position = msg->actual.positions[0]; 00218 feedback.velocity = msg->actual.velocities[0]; 00219 feedback.error = msg->error.positions[0]; 00220 active_goal_.publishFeedback(feedback); 00221 00222 if (fabs(msg->actual.positions[0] - active_goal_.getGoal()->position) < goal_threshold_) 00223 { 00224 active_goal_.setSucceeded(); 00225 has_active_goal_ = false; 00226 } 00227 } 00228 00229 }; 00230 00231 int main(int argc, char** argv) 00232 { 00233 ros::init(argc, argv, "position_joint_action_node"); 00234 ros::NodeHandle node; 00235 SingleJointPositionNode a(node); 00236 ros::spin(); 00237 return 0; 00238 }