[Documentation] [TitleIndex] [WordIndex

Only released in EOL distros:  

rovio: rovio_av | rovio_ctrl | rovio_shared

Package Summary

The rovio_shared package contains standard messages and services as well as a library that can be used to communicate with a WowWee Rovio.

rovio: rovio_av | rovio_ctrl | rovio_shared

Package Summary

Standard Messages and Services for the WowWee Rovio

rovio: rovio_av | rovio_ctrl | rovio_shared

Package Summary

Standard Messages and Services for the WowWee Rovio

About

The rovio_shared package contains a library that is used to communicate with the Rovio. This package and library are intended to be used with the packages provided in the rovio stack; however, it is possible to compile and use the library in your own packages as well.

Newly proposed, mistyped, or obsolete package. Could not find package "rovio_shared" in rosdoc: /var/www/docs.ros.org/en/api/rovio_shared/manifest.yaml

Installation

To install the rovio stack, you can choose to either install from source, or from the Ubuntu package:

Source

To install from source, execute the following:

Ubuntu Package

To install the Ubuntu package, execute the following:

Library Example

While the rovio_http library was constructed primarily for use within the rovio stack's packages, it is possible to utilize its functionality in any ROS node.

The example below has the Rovio drive forwards until the user issues a ctrl-c command. Other information on the rovio_http library can be found in the API.

The C++ Code

   1 /*
   2  * A simple example that utilizes the rovio_http library from the
   3  * rovio_shared package.
   4  *
   5  * Author: Russell Toris - rctoris@wpi.edu
   6  *
   7  * Version: September 1, 2011
   8  */
   9 
  10 #include <ros/ros.h>
  11 #include <rovio_shared/rovio_http.h>
  12 
  13 int main(int argc, char **argv)
  14 {
  15   // initialize ROS and the node
  16   ros::init(argc, argv, "rovio_http_example");
  17   ros::NodeHandle node;
  18 
  19   // create the rovio_http object to talk to Rovio
  20   rovio_http rovio("admin", "your_password");
  21 
  22   // update at 5 Hz
  23   ros::Rate loop_rate(5);
  24   // continue until a ctrl-c has occurred
  25   while (ros::ok())
  26   {
  27     // always good practice to spin in a loop
  28     ros::spinOnce();
  29 
  30     // send a command to move forwards
  31     rovio_response *resp = rovio.send(
  32         "http://192.168.1.110/rev.cgi?Cmd=nav&action=18&drive=1&speed=5");
  33     // print out the response
  34     ROS_INFO("%s", resp->data);
  35     // always free the response once we are done with it
  36     free(resp);
  37 
  38     // wait for the timer
  39     loop_rate.sleep();
  40   }
  41 }

Code Explanation

Now that we have a running example, let's look at each piece.

  10 #include <ros/ros.h>
  11 #include <rovio_shared/rovio_http.h>
  12 

In order to utilize the rovio_http library in ROS, we must import the both the standard ROS and rovio_http library headers.

  15   // initialize ROS and the node
  16   ros::init(argc, argv, "rovio_http_example");
  17   ros::NodeHandle node;

Create and initialize your ROS node as with any other ROS node.

  19   // create the rovio_http object to talk to Rovio
  20   rovio_http rovio("admin", "your_password");

Create a rovio_http object by supplying it with the username and password to your Rovio. This object with use libcurl to communicate to the Rovio's HTTP server.

  22   // update at 5 Hz
  23   ros::Rate loop_rate(5);
  24   // continue until a ctrl-c has occurred
  25   while (ros::ok())

In this example we enter a loop that runs at 5 Hz.

  28     ros::spinOnce();

Even though we do not have any topics or services, it is still good practice to spin inside of the main loop in a node.

  30     // send a command to move forwards
  31     rovio_response *resp = rovio.send(
  32         "http://192.168.1.110/rev.cgi?Cmd=nav&action=18&drive=1&speed=5");
  33     // print out the response
  34     ROS_INFO("%s", resp->data);
  35     // always free the response once we are done with it
  36     free(resp);

Here we construct and send an HTTP command based on the Rovio API. In this example we will tell to Rovio to drive forwards at speed 5. This function will return a pointer to a 'rovio_response' struct containing the response from the Rovio. Even if this information is not need it is important to always free this struct once you are finished to prevent a memory leak.

  38     // wait for the timer
  39     loop_rate.sleep();

Once the command has been sent we wait for the ROS timer to go off before continuing.

Support

Please send bug reports to the GitHub Issue Tracker. Feel free to contact me at any point with questions and comments.


wpi.png

rail.png


2024-11-30 17:53