$search
00001 /* 00002 * simple_base_control.cpp 00003 * 00004 * Created on: Sep 10, 2010 00005 * Author: Sebastian Haug | Bosch RTC 00006 * 00007 * Controls PR2 Base. Provides easy to use high level interface 00008 * to move and rotate base. No further services have to be launched. 00009 * 00010 * How to use: 00011 * - Configured as Library. Add dependency to in simple_base_control_cpp 00012 * in own ROS package and instantiate SimpleBaseControl object. 00013 */ 00014 00015 #include "simple_robot_control/base_control.h" 00016 00017 namespace simple_robot_control{ 00018 00019 Base::Base() 00020 { 00021 init(); 00022 } 00023 00024 Base::~Base() 00025 { } 00026 00027 void Base::init() 00028 { 00029 // init cmd_ 00030 cmd_.linear.x = cmd_.linear.y = cmd_.angular.z = 0; 00031 00032 // register publisher 00033 pub_base_vel_ = nh_.advertise<geometry_msgs::Twist>("/base_controller/command", 1); 00034 } 00035 00036 // Drive forward a specified distance in m with given speed in m/s 00037 bool Base::driveForward(double distance, double speed) 00038 { 00039 geometry_msgs::Twist vel; 00040 vel.linear.x = std::abs(speed); 00041 00042 return drive(distance, vel); 00043 } 00044 00045 // Drive right a specified distance in m with given speed in m/s 00046 bool Base::driveRight(double distance, double speed) 00047 { 00048 geometry_msgs::Twist vel; 00049 vel.linear.y = -std::abs(speed); 00050 00051 return drive(distance, vel); 00052 } 00053 00054 // Drive back a specified distance in m with given speed in m/s 00055 bool Base::driveBack(double distance, double speed) 00056 { 00057 geometry_msgs::Twist vel; 00058 vel.linear.x = -std::abs(speed); 00059 00060 return drive(distance, vel); 00061 } 00062 00063 // Drive left a specified distance in m with given speed in m/s 00064 bool Base::driveLeft(double distance, double speed) 00065 { 00066 geometry_msgs::Twist vel; 00067 vel.linear.y = std::abs(speed); 00068 00069 return drive(distance, vel); 00070 } 00071 00072 // Drive a specified distance (based on base odometry information) with given velocity Twist (vector) 00073 bool Base::drive(double distance, const geometry_msgs::Twist& velocity) 00074 { 00075 tf::StampedTransform start_transform; 00076 tf::StampedTransform current_transform; 00077 00078 // Wait and get transform 00079 tf_listener_odom_.waitForTransform("base_footprint", "odom_combined", ros::Time(0), ros::Duration(5.0)); 00080 tf_listener_odom_.lookupTransform("base_footprint", "odom_combined", ros::Time(0), start_transform); 00081 00082 // Set cmd_ to velocity and clear angular and linear.z; 00083 cmd_ = velocity; 00084 cmd_.angular.x = cmd_.angular.y = cmd_.angular.z = cmd_.linear.z = 0; 00085 00086 00087 00088 // Loop until pos reached 00089 ros::Rate rate(PUBLISH_RATE_); 00090 bool done = false; 00091 00092 while (!done && nh_.ok()) { 00093 // Send the drive command 00094 pub_base_vel_.publish(cmd_); 00095 rate.sleep(); 00096 00097 // Get the current transform 00098 try { 00099 tf_listener_odom_.lookupTransform("base_footprint", "odom_combined", ros::Time(0), current_transform); 00100 } catch (tf::TransformException ex) { 00101 ROS_ERROR("%s",ex.what()); 00102 break; 00103 } 00104 00105 // See how far we've traveled 00106 tf::Transform relative_transform = start_transform.inverse() * current_transform; 00107 double dist_moved = relative_transform.getOrigin().length(); 00108 00109 00110 if (dist_moved >= distance) 00111 done = true; 00112 } 00113 return done; 00114 } 00115 00116 // Rotate as specified in rad (based on base odometry information) with given speed in rad/s 00117 bool Base::turn(bool clockwise, double radians, double speed) 00118 { 00119 while (radians < 0) radians += 2 * M_PI; 00120 while (radians > 2 * M_PI) radians -= 2 * M_PI; 00121 00122 tf::StampedTransform start_transform; 00123 tf::StampedTransform current_transform; 00124 00125 // Wait and get transform 00126 tf_listener_odom_.waitForTransform("base_footprint", "odom_combined", ros::Time(0), ros::Duration(5.0)); 00127 tf_listener_odom_.lookupTransform("base_footprint", "odom_combined", ros::Time(0), start_transform); 00128 00129 // Set cmd_ 00130 cmd_.linear.x = cmd_.linear.y = cmd_.linear.z = 0.0; 00131 cmd_.angular.z = speed; 00132 if (clockwise) 00133 cmd_.angular.z = -speed ; 00134 00135 00136 00137 // The axis we want to be rotating by 00138 tf::Vector3 desired_turn_axis(0, 0, 1); 00139 if (!clockwise) 00140 desired_turn_axis = -desired_turn_axis; 00141 00142 // Loop until finished turn 00143 ros::Rate rate(PUBLISH_RATE_); 00144 bool done = false; 00145 00146 while (!done && nh_.ok()) { 00147 // Send the drive command 00148 pub_base_vel_.publish(cmd_); 00149 rate.sleep(); 00150 00151 // Get the current transform 00152 try { 00153 tf_listener_odom_.lookupTransform("base_footprint", "odom_combined", ros::Time(0), current_transform); 00154 } catch (tf::TransformException ex) { 00155 ROS_ERROR("%s",ex.what()); 00156 break; 00157 } 00158 tf::Transform relative_transform = start_transform.inverse() * current_transform; 00159 tf::Vector3 actual_turn_axis = relative_transform.getRotation().getAxis(); 00160 double angle_turned = relative_transform.getRotation().getAngle(); 00161 if (fabs(angle_turned) < 1.0e-2) 00162 continue; 00163 00164 if (actual_turn_axis.dot(desired_turn_axis) < 0) 00165 angle_turned = 2 * M_PI - angle_turned; 00166 00167 if (angle_turned > radians) 00168 done = true; 00169 } 00170 return done; 00171 } 00172 00173 }