rovio_move.cpp
Go to the documentation of this file.
00001 
00012 #include <algorithm>
00013 #include <geometry_msgs/Twist.h>
00014 #include <math.h>
00015 #include <ros/ros.h>
00016 #include <rovio_shared/man_drv.h>
00017 #include <rovio_shared/rovio_http.h>
00018 #include <rovio_ctrl/rovio_move.h>
00019 #include <sstream>
00020 #include <string>
00021 
00022 using namespace std;
00023 
00024 move_controller::move_controller()
00025 {
00026   string user;
00027   string pass;
00028 
00029   // check for all the correct parameters
00030   if (!node.getParam(USER, user))
00031   {
00032     ROS_ERROR("Parameter %s not found.", USER);
00033     exit(-1);
00034   }
00035   if (!node.getParam(PASS, pass))
00036   {
00037     ROS_ERROR("Parameter %s not found.", PASS);
00038     exit(-1);
00039   }
00040   if (!node.getParam(HOST, host))
00041   {
00042     ROS_ERROR("Parameter %s not found.", HOST);
00043     exit(-1);
00044   }
00045 
00046   // create the communication object to talk to Rovio
00047   rovio = new rovio_http(user, pass);
00048 
00049   // add subscriptions that will control the Rovio
00050   man_drv = node.subscribe<rovio_shared::man_drv>("man_drv", 10, &move_controller::man_drv_callback, this);
00051   cmd_vel = node.subscribe<geometry_msgs::Twist>("cmd_vel", 10, &move_controller::cmd_vel_callback, this);
00052 
00053   drive = 0;
00054   speed = 0;
00055   rotate = 0;
00056 
00057   ROS_INFO("Rovio Move Controller Initialized");
00058 }
00059 
00060 move_controller::~move_controller()
00061 {
00062   // free up the rovio_http object
00063   delete rovio;
00064 }
00065 
00066 void move_controller::update()
00067 {
00068   // check for a drive command
00069   if (drive > 0)
00070   {
00071     // build the URL command and send it
00072     stringstream ss;
00073     ss << "http://" << host.c_str() << "/rev.cgi?Cmd=nav&action=18&drive=" << drive << "&speed=" << speed;
00074     rovio_response *buf = rovio->send(ss.str().c_str());
00075     rovio_response_clean(buf);
00076   }
00077   // check for a rotation command
00078   if (rotate > 0)
00079   {
00080     // build the URL command and send it
00081     stringstream ss;
00082     ss << "http://" << host.c_str() << "/rev.cgi?Cmd=nav&action=18&drive=6&speed=" << rotate;
00083     rovio_response *buf = rovio->send(ss.str().c_str());
00084     rovio_response_clean(buf);
00085   }
00086   else if (rotate < 0)
00087   {
00088     // build the URL command and send it
00089     stringstream ss;
00090     ss << "http://" << host.c_str() << "/rev.cgi?Cmd=nav&action=18&drive=5&speed=" << -rotate;
00091     rovio_response *buf = rovio->send(ss.str().c_str());
00092     rovio_response_clean(buf);
00093   }
00094 }
00095 
00096 void move_controller::man_drv_callback(const rovio_shared::man_drv::ConstPtr &msg)
00097 {
00098   // check to see if all the requests are valid
00099   if (msg->drive < rovio_shared::man_drv::MIN_DRIVE_VAL || msg->drive > rovio_shared::man_drv::MAX_DRIVE_VAL)
00100   {
00101     ROS_ERROR(
00102         "Manual Drive 'drive' value of %i out of range [%i,%i].", msg->drive, rovio_shared::man_drv::MIN_DRIVE_VAL, rovio_shared::man_drv::MAX_DRIVE_VAL);
00103     return;
00104   }
00105   if (msg->speed < rovio_shared::man_drv::MIN_SPEED_VAL || msg->speed > rovio_shared::man_drv::MAX_SPEED_VAL)
00106   {
00107     ROS_ERROR(
00108         "Manual Drive 'speed' value of %i out of range [%i,%i].", msg->speed, rovio_shared::man_drv::MIN_SPEED_VAL, rovio_shared::man_drv::MAX_SPEED_VAL);
00109     return;
00110   }
00111 
00112   // set the values
00113   drive = msg->drive;
00114   speed = msg->speed;
00115 }
00116 
00117 void move_controller::cmd_vel_callback(const geometry_msgs::Twist::ConstPtr &msg)
00118 {
00119   // check if we are moving left or right
00120   if (msg->linear.x == 0 && msg->linear.y > 0)
00121   {
00122     // drive left
00123     drive = 3;
00124   }
00125   else if (msg->linear.x == 0 && msg->linear.y < 0)
00126   {
00127     // drive right
00128     drive = 4;
00129   }
00130   else
00131   {
00132     // calculate the angle
00133     double angle = atan2(msg->linear.x, msg->linear.y);
00134     // bound the movements to one of the discrete Rovio drive commands
00135     if (msg->linear.x > 0 && angle <= 5 * M_PI / 8 && angle >= 3 * M_PI / 8)
00136     {
00137       // drive forwards
00138       drive = 1;
00139     }
00140     else if (msg->linear.x > 0 && msg->linear.y > 0 && angle < 3 * M_PI / 8 && angle >= M_PI / 8)
00141     {
00142       // drive forwards and right
00143       drive = 8;
00144     }
00145     else if (msg->linear.y > 0 && (angle >= -1 * M_PI / 8 || angle >= 3 * M_PI / 8))
00146     {
00147       // drive right
00148       drive = 4;
00149     }
00150     else if (msg->linear.x < 0 && msg->linear.y > 0 && angle < -1 * M_PI / 8 && angle >= -3 * M_PI / 8)
00151     {
00152       // drive backwards and right
00153       drive = 10;
00154     }
00155     else if (msg->linear.x < 0 && angle <= -3 * M_PI / 8 && angle >= -5 * M_PI / 8)
00156     {
00157       // drive backwards
00158       drive = 2;
00159     }
00160     else if (msg->linear.x < 0 && msg->linear.y < 0 && angle <= -5 * M_PI / 8 && angle >= -7 * M_PI / 8)
00161     {
00162       // drive backwards and left
00163       drive = 9;
00164     }
00165     else if (msg->linear.y < 0 && (angle < -7 * M_PI / 8 || angle >= 7 * M_PI / 8))
00166     {
00167       // drive left
00168       drive = 3;
00169     }
00170     else if (msg->linear.x > 0 && msg->linear.y < 0 && angle < 7 * M_PI / 8 && angle >= 5 * M_PI / 8)
00171     {
00172       // drive forwards and left
00173       drive = 7;
00174     }
00175     else
00176     {
00177       // no movement
00178       drive = 0;
00179     }
00180   }
00181 
00182   // get the rotational speed
00183   rotate = -msg->angular.z * 10.0;
00184 
00185   // get the linear speed (10 being the fastest)
00186   speed = min(10, (int)(sqrt(pow(msg->linear.x, 2.0) + pow(msg->linear.y, 2.0)) * 10));
00187 }
00188 
00189 int main(int argc, char **argv)
00190 {
00191   // initialize ROS and the node
00192   ros::init(argc, argv, "rovio_move");
00193 
00194   // initialize the Rovio controller
00195   move_controller controller;
00196 
00197   // update at 5 Hz
00198   ros::Rate loop_rate(5);
00199   // continue until a ctrl-c has occurred
00200   while (ros::ok())
00201   {
00202     ros::spinOnce();
00203     // update the motors
00204     controller.update();
00205     loop_rate.sleep();
00206   }
00207 }


rovio_ctrl
Author(s): Russell Toris
autogenerated on Mon Oct 6 2014 07:13:12