• attachment:PLAYER-to-ROS.txt of ROS/PlayerIntegration

Attachment 'PLAYER-to-ROS.txt'

Download

   1                 Notes on converting player code to ROS
   2 
   3 
   4 BUILD TREE
   5 ----------
   6 
   7 ROS code is organized into stacks and packages.  Stacks are
   8 subdirectories in the tree with package directories inside them.  Each
   9 stack or package has a global name in the ROS package name space, so
  10 their directory names need to be unique and descriptive.
  11 
  12 A stack directory is identified by its <stack.xml> file.  The rosstack
  13 command should be able to find and print information about it.
  14 
  15   http://www.ros.org/wiki/Stacks/CreateStack?highlight=(stack)|(creating)
  16 
  17 A package directory is identified by a manifest.xml file describing
  18 its name, authors, licences, exports and dependencies.  Once that file
  19 exists, the rospack command should be able to find and print
  20 information about it.
  21 
  22   http://www.ros.org/wiki/ROS/Tutorials/CreatingPackage?highlight=(BeginnerCategory)
  23 
  24 Remove any old SConscript files, they are replaced by CMakeLists.txt
  25 in the ROS build scheme.  You should be able to build any package
  26 using the rosmake command.
  27 
  28   http://www.ros.org/wiki/ROS/BuildSystemUsage
  29 
  30 
  31 DRIVERS
  32 -------
  33 
  34 Convert player drivers to ROS nodes.  The class inherited from the
  35 player Driver class is no longer needed and just adds unnecessary
  36 complexity.  
  37 
  38 Make a simple C++ main program, something like this:
  39 
  40   int main(int argc, char** argv)
  41   {
  42     ros::init(argc, argv, NODE);
  43     ros::NodeHandle node;
  44   
  45     // topics to read and write
  46     brake_cmd = node.subscribe(NODE "/cmd", 10, ProcessCommand,
  47                                ros::TransportHints().tcpNoDelay(true));
  48     brake_state = node.advertise<art_brake::State>(NODE "/state", 10);
  49   
  50     if (GetParameters() != 0)             // from the player constructor
  51       return 1;
  52   
  53     ros::Rate cycle(HERTZ_BRAKE);         // set driver cycle rate
  54   
  55     if (Setup() != 0)                     // from the player Setup()
  56       return 2;
  57   
  58     // Main loop; grab messages off our queue and republish them via ROS
  59     while(ros::ok())
  60       {
  61         ...                               // activities from player Main()
  62         cycle.sleep();                    // sleep until next cycle
  63       }
  64   
  65     Shutdown();
  66   
  67     return 0;
  68   }
  69 
  70 
  71 
  72 INTERFACES
  73 ----------
  74 
  75 Most player interfaces have ROS equivalents, here are some examples.
  76 The player code snippet is shown first, followed by an indented ROS
  77 version, with comments (where appropriate).
  78 
  79 
  80 ART_ERROR(msg);
  81 
  82   ROS_ERROR(msg) or ROS_FATAL(msg), depending on severity.
  83 
  84 ART_MSG(level, msg);
  85 
  86   ROS_INFO(msg) if infrequent, or ROS_DEBUG(msg) if recurring
  87 
  88   The verbose configuration parameter is not needed.  Use
  89   rxloggerlevel command to turn debug output on or off dynamically at
  90   run time.  Much nicer.
  91 
  92 ART_WARN(msg);
  93 
  94   ROS_WARN(msg);
  95 
  96 DTOR(deg);
  97 
  98   angles::from_degees(deg);
  99 
 100   // This requires adding <depend package="angles"/> to your
 101   // manifest.xml, then adding #include <angles/angles.h> to the source
 102   // file.
 103 
 104 extern PlayerTime* GlobalTime;
 105 GlobalTime->GetTimeDouble(&time);
 106 
 107   double time = ros::Time::now().toSec();
 108 
 109 // main loop
 110 for(;;)
 111   {
 112     // see if we are supposed to exit
 113     pthread_testcancel();
 114     ...
 115 
 116   // main loop
 117   while(ros::ok())
 118     {
 119       ...
 120 
 121 PLAYER_ERROR(msg);
 122 
 123   ROS_ERROR(msg) or ROS_FATAL(msg), depending on severity.
 124 
 125 PLAYER_MSGn(level, msg);
 126 
 127   ROS_INFO(msg) if infrequent, or ROS_DEBUG(msg) if recurring
 128 
 129 PLAYER_WARN(msg);
 130 
 131   ROS_WARN(msg);
 132 
 133 const char *port;                       // tty port name
 134 port = cf->ReadString(section, "port", "/dev/null");
 135 PLAYER_MSG1(2, CLASS " constructor: brake port = %s", port);
 136 
 137   // use private node handle to get parameters
 138   ros::NodeHandle mynh("~");
 139   std::string port;                     // tty port name
 140 
 141   if (!mynh.getParam("port", port))
 142       port = "/dev/null";
 143   ROS_INFO("brake port = %s", port.c_str());
 144 
 145 
 146 RTOD(rad);
 147 
 148   angles::to_degrees(rad);
 149 
 150   // See DTOR() for dependencies.

Attached Files

To refer to attachments on a page, use attachment:filename, as shown below in the list of files. Do NOT use the URL of the [get] link, since this is subject to change and can break easily.
  • [get | view] (2009-09-28 01:17:17, 3.8 KB) [[attachment:PLAYER-to-ROS.txt]]
 All files | Selected Files: delete move to page copy to page

You are not allowed to attach a file to this page.