00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2012, 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 /* Author: Ioan Sucan */ 00036 00037 #include <ros/ros.h> 00038 #include <moveit/sensor_manager/sensor_manager.h> 00039 #include <pluginlib/class_list_macros.h> 00040 #include <boost/math/constants/constants.hpp> 00041 00042 #include <actionlib/client/simple_action_client.h> 00043 #include <pr2_controllers_msgs/PointHeadAction.h> 00044 00045 namespace pr2_moveit_sensor_manager 00046 { 00047 00048 class Pr2MoveItSensorManager : public moveit_sensor_manager::MoveItSensorManager 00049 { 00050 public: 00051 00052 Pr2MoveItSensorManager() : node_handle_("~") 00053 { 00054 node_handle_.param("head_pointing_frame", head_pointing_frame_, std::string("/camera")); 00055 head_action_client_.reset(new actionlib::SimpleActionClient<pr2_controllers_msgs::PointHeadAction>("/head_traj_controller/point_head_action", true)); 00056 } 00057 00058 virtual ~Pr2MoveItSensorManager() 00059 { 00060 } 00061 00062 virtual void getSensorsList(std::vector<std::string> &names) const 00063 { 00064 names.resize(1); 00065 names[0] = "head"; 00066 } 00067 00068 virtual moveit_sensor_manager::SensorInfo getSensorInfo(const std::string &name) const 00069 { 00070 // I made this up. 00071 moveit_sensor_manager::SensorInfo si; 00072 if (name == "head") 00073 { 00074 si.origin_frame = head_pointing_frame_; 00075 si.min_dist = 0.1; 00076 si.max_dist = 3.0; 00077 si.x_angle = boost::math::constants::pi<double>() / 3.0; 00078 si.y_angle = boost::math::constants::pi<double>() / 3.0; 00079 } 00080 else 00081 ROS_ERROR("Unknown sensor: '%s'", name.c_str()); 00082 return si; 00083 } 00084 00085 virtual bool hasSensors() const 00086 { 00087 return true; 00088 } 00089 00090 virtual bool pointSensorTo(const std::string &name, const geometry_msgs::PointStamped &target, moveit_msgs::RobotTrajectory &sensor_trajectory) 00091 { 00092 if (name != "head") 00093 { 00094 ROS_ERROR("Unknown sensor: '%s'", name.c_str()); 00095 return false; 00096 } 00097 if (!head_action_client_->isServerConnected()) 00098 { 00099 ROS_ERROR("Head action server is not connected"); 00100 return false; 00101 } 00102 00103 sensor_trajectory = moveit_msgs::RobotTrajectory(); 00104 00105 pr2_controllers_msgs::PointHeadGoal goal; 00106 goal.pointing_frame = head_pointing_frame_; 00107 goal.max_velocity = 1.0; 00108 goal.pointing_axis.x = 0.0; 00109 goal.pointing_axis.y = 0.0; 00110 goal.pointing_axis.z = 1.0; 00111 goal.target = target; 00112 actionlib::SimpleClientGoalState result = head_action_client_->sendGoalAndWait(goal, ros::Duration(5.0)); 00113 if (result == actionlib::SimpleClientGoalState::SUCCEEDED) 00114 return true; 00115 else 00116 { 00117 ROS_WARN_STREAM("Head moving action is done with state " << result.toString() << ": " << result.getText()); 00118 return false; 00119 } 00120 } 00121 00122 protected: 00123 00124 ros::NodeHandle node_handle_; 00125 std::string head_pointing_frame_; 00126 boost::shared_ptr<actionlib::SimpleActionClient<pr2_controllers_msgs::PointHeadAction> > head_action_client_; 00127 00128 }; 00129 00130 PLUGINLIB_EXPORT_CLASS(pr2_moveit_sensor_manager::Pr2MoveItSensorManager, 00131 moveit_sensor_manager::MoveItSensorManager); 00132 }