Home

TraxBot - ROS Driver Guide v1.1 - ISR

image

Contents

1. Traxster Robot ROS Driver Guide 2 3 Available TraxBot driver Topics e To verify the available topics simply run in a console SOs Oe nee The possible topics available for this TraxBot driver are driverTemperature std_msgs Float32 OMNI 3MD temperature robotID std msgs Int16 Robot ID integer std msgs Int32 Encoder motor 1 in pulses std msgs Int32 Encoder motor 2 in pulses a Velocity commands u Activate callback function to stop Acti Ilback f i encodersReset std_msgs Empty reset encoders Subscribers Traxster Robot ROS Driver Guide 12 Appendix A Protocol Table A 1 Protocol data insertion The communication frame between ROS and the Arduino follows the following protocol INITIAL Char COMMAND SEP 1 PARAMETER SEP 2 PARAMETER SEP nPARAMETER FINAL Char e rm mmm mom mm Pe O A 2 Protocol data insertion example This protocol accepts 3 types of data Initial configuration Cinematic commands and sensors readings Example of a linear move command to the motors Motorl Speed Motor2 Speed and gt direction mett direction mor 9 1 40 1 40 jel A 2 Communication protocol technical info Serial Baud rate 19200 All inserted values must be integers Traxster Robot ROS Driver Guide 14 Reply l Define PID motor controller gains Kp Ki and Kd 12 Kp K1 Kde 0 65535 Set
2. Examples To graph the data in different plots rxplot topici field1 topic2 field2 To graph the data all on the same plot rxplot topici field1 topic2 field2 To graph multiple fields of a message rxplot topici field1 field2 field3 rxbag A tool for visualizing inspecting and replaying histories bag files of ROS messages rxbag full_run_2009 11 06 bag H e DECORO a Q Q in Nov 66 2009 11 57 57 23 base_sca laser_tilt n tilt controllerflaser scanner signal RIINA AA 0000000100004 006 00000000 060100000 100000000000 narrow_stereo left camera_info nE I E E F r ET t narrow_stereojleft image_raw IR i F narrow_stereo right camera_info narrow stereo right image raw prosilica cam info prosilica image throttled tilt scan wide stereo left camera info wide stereo left image raw wide stereo right camera info wide stereo right image raw Usage rxbag bag file bag rxconsole A tool for displaying and filtering messages published on rosout rxconsole ENES Message Severity Node Publishing narrow_stereo_textured left image_rect Info narrow_s Publishing narrow_stereo_textured right image_mono Info maron Publishing narrow_stereo_textured right image_rect Info narrow_s d Some frames were never seen The dropped packet count will be incorrect Warn wide_ste Some frames were never seen The dropped packet count will be incorrect Warn narr
3. Cheat Sheet Filesystem Command line Tools rospack rosstack A tool inspecting packages stacks roscd Changes directories to a package or stack rosls Lists package or stack information Creates a new ROS package Creates a new ROS stack roscreate pkg roscreate stack rosdep Installs ROS package system dependen cles rosmake Builds a ROS package roswtf Displays a errors and warnings about a running ROS system or launch file rxdeps Displays package structure and depen dencies Usage rospack find package roscd package subdir rosls package subdir roscreate pkg package name rosmake package rosdep install package roswtf or roswtf file rxdeps options A A A A YN YN KA Common Command line Tools roscore A collection of nodes and programs that are pre requisites of a ROS based system You must have a roscore running in order for ROS nodes to communicate roscore is currently defined as master parameter server rosout Usage roscore rosmsg rossrv rosmsg rossrv displays Message Service msg srv data structure definitions Commands rosmsg show rosmsg users rosmsg md5 rosmsg package rosnode packages Display the fields in the msg Search for code using the msg Display the msg md5 sum List all the messages in a package List all the packages with messages Examples Display the Pose msg rosmsg show Pose List the messages in nav_msgs rosmsg package
4. Sl ls e Install the serial communication stack stack S svn co http isr uc ros pkg googlecode com svn stacks serial communication trunk S mv trunk se ale ns o S rosmake SS olaconmnunicanion e Install the TraxBot driver stack Ss o is aaaea akoa ank Se o S rosmake pls ra xbor Traxster Robot ROS Driver Guide 5 1 4 Download and Install the Arduino IDE It is neccessary to install the Arduino IDE to upload the firmware to the TraxBot s Arduino O OQ Blink Arduino 1 0 File Edit Sketch Tools Help Blin Turns on an LED on for one second then off for one second repeatedly This example code is in the public domain KS vold setup ff initialize the digital pin as an output Pin 13 has an LED connected on most Arduino boards pinMode 13 OUTPUT void loop digitalWrite 13 HIGH set the LED on y i q ts mmm e 1 Binary sketch size 1026 bytes of a 30720 byte maximum Arduino Duemilanove w ATrnega328 on devittyUSBO e Install the Arduino IDE in Ubuntu SE BTE OE oo eS salda dina Verify if the installed IDE version is v1 0 or higher Otherwise download it from http arduino cc en Main Software Traxster Robot ROS Driver Guide 1 5 Upload firmware to Arduino UNO e After the installation run the Arduino IDE a Open the driver firmware in the Arduino IDE go to File gt Open and insert the following path folder home USER stacks mrl robots traxbot robot u
5. take awhile Press Ctrl C to interrupt Done checking log file disk usage Usage is lt 1GB started roslaunch server http chopin 04 49806 ros comm version 1 6 6 rosversion rosdistro NODES auto starting new master process master started with pid 3908 ROS MASTER URI http chopin 04 11311 setting run id to ad59f3d8 ccd6 llel 9adc 20cf300db6c9 process rosout 1 started with pid 3932 started core service rosout e After the installation run the Arduino IDE rosrun IEF LI A ONO SP OMEN Ne TED ANON EO NEN er The driver assumes dev ttyACMO0 as the default serial port If the robot is connected on a different serial port e g dev ttyACMT you should run e mrl chopin 04 File Edit View roscore http chopin 04 11311 mrl chopin 04 rosrun traxbot robot robot node a INFO INFO INFO INFO INFO INFO INFO ER At this moment the driver 1s activated and ready to send velocity commands to the robot and receive any kind of information from 1t depending on the desired application 1342183008 977131564 1342183009 001600871 1342183009 001992890 1342183009 002268973 1342183009 002553507 1342183009 002760516 1342183009 002960612 Search Terminal Tabs Help mrl chopin 04 mrl chopin 04 Robot Getting ID Robot Reply 5 2590 263 960 2 0e Temperature 25 90 C OMNI Firmware 2 63 Battery 9 60 V VDriver 2 00 ID 0
6. Find services by service type rosservice call rosservice args rosservice type rosservice uri rosservice find Examples Call a service from the command line rosservice call add_two_ints 1 2 Pipe the output of rosservice to rossrv to view the srv type rosservice type add_two_ints rossrv show Display all services of a particular type rosservice find rospy_tutorials AddTwoInts Logging Command line Tools rosbag This is a set of tools for recording from and playing back to ROS topics It is intended to be high performance and avoids deserialization and reserializationof the messages rosbag record will generate a bag file so named for historical reasons with the contents of all topics that you pass to it Examples Record all topics rosbag record a Record select topics rosbag record topici topic2 rosbag play will take the contents of one or more bag file and play them back in a time synchronized fashion Examples Replay all messages without waiting rosbag play a demo_log bag Replay several bag files at once rosbag play demol bag demo2 bag Graphical Tools rxgraph Displays a graph of the ROS nodes that are currently running as well as the ROS topics that connect them random_number_generator rosout_agg Usage rxgraph rxplot A tool for plotting data from one or more ROS topic fields using matplotlib 90 turtlel pose x turtlel pose y
7. Institute of Systems and Robotics TraxBot ROS Driver Guide Andr Ara jo David Portugal Micael Couceiro Rui P Rocha ROS Driver Guide TraxBot Platform VII July 13 2012 Traxster Robot ROS Driver Guide Mobile Robotic Laboratory MRL Institute of Systems and Robotics University of Coimbra ISR UC Portugal Contact person Rui P Rocha E mail address rprocha isr uc pt Webpage http paloma isr uc pt mrl Authors contact Andr Ara jo David Portugal Micael Couceiro E mail address aaraujo isr uc pt davidbsp isr uc pt micaelcouceiro isr uc pt Traxster Robot ROS Driver Guide Contents Chapter 1 Installation Guide pill 3 I Requitemene dA T A 4 li ROS TES Ore ania OI ricer 5 1 3 Download and Install the TraxBot driver nono nnnnnos 5 1 4 Download and Install the Arduino IDE nennen 6 Lo Upload firmware to Arduino UND en 7 LO EO LU ATAU Dorsten eta cece ene nent 8 1 621 Hardware Soup 8 1 6 2 Uploading Code 10 Arduo sn sn IB 8 Chaplin Usos 9 le ISS basa 10 22 Running Trax Bot driver im ROS a 11 Zo Available Trax Bor driver TODE S vaa 12 Appendix 7 Protocol Tables 13 Al Protocol data Insert on a innean os 14 AZ Protocol das 1NScruon example ia er 14 A 2 Communication protocol technical info nn nnnnnnnnnnnnnenn 14 Appendix B ROS Cheat Sheet ke kreis 16 Traxster Robot ROS Driver Guide 2 Chapter 1 Insta
8. ctive topics Publish data to topic Print topic type Find topics by type rostopic pub rostopic type rostopic find Examples Publish hello at 10 Hz rostopic pub r 10 topic_name std_msgs String hello Clear the screen after each message is published rostopic echo c topic_name Display messages that match a given Python expression rostopic echo filter m data foo topic_name Pipe the output of rostopic to rosmsg to view the msg type rostopic type topic_name rosmsg show rosparam A tool for getting and setting ROS parameters on the parameter server using YAML encoded files Commands rosparam set rosparam get rosparam load rosparam dump rosparam delete rosparam list Set a parameter Get a parameter Load parameters from a file Dump parameters to a file Delete a parameter List parameter names Examples List all the parameters in a namespace rosparam list namespace Setting a list with one as a string integer and float rosparam set foo 1 1 1 0 Dump only the parameters in a specific namespace to file rosparam dump dump yaml namespace rosservice A tool for listing and querying ROS services Commands rosservice list rosservice node Print information about active services Print the name of the node providing a service Call the service with the given args List the arguments of a service Print the service type Print the service ROSRPC uri
9. encoders prescaler 3 enc valuee enc enconder 1 2 value value 0 4 Set encoder value 4 enc valuee enc enconder 1 2 value value 0 65535 Provides robot information temp OMNI 3MD temperature firm OMNI 3MD firmware bat Battery power r firm Robot firmware r id Robot ID Provides encoder readings 6 encl enc2e encl encoder 1 Left enc2 encoder 2 Right Provides sonars readings sonl encoder 1 Front son2 encoder 2 Left son3 encoder 2 Right Provides sonars and encoders readings encl encoder 1 Left enc2 encoder 2 Right sonl encoder 1 Front son2 encoder 2 Left son3 encoder 2 Right Send linear move commands with PID controller dirl direction motor 1 1 2 9 dirl speed1 dir2 speed2e speedl speed motor 1 0 100 dir2 direction motor 2 1 2 speed2 speed motor 2 0 100 Send linear move dirl direction motor 1 1 2 10 dirl speed1 dir2 speed2e speedl speed motor 1 0 100 dir2 direction motor 2 1 2 speed2 speed motor 2 0 100 13e to the console 13 0 1 e Check Debug mode 0 1 Description 15 temp firm bat r firm r ide 7 sonl son2 son3e 8 encl enc2 son1 son2 son3e 114 0 1 e Set debug mode 0 1 15e 15 0 1 e Info stream mode 0 1 Streaming encoder readings 6 encl enc2e encl encoder 1 Left enc2 encoder 2 Right Traxster Robot ROS Driver Guide 15 Appendix B ROS Cheat Sheet ROS
10. irst initialized power source battery or USB power 1 6 2 Uploading code to Arduino If the XBee shield is mounted on top of the Arduino Uno board its switch should be in USB mode in order to upload code otherwise t will not be possible 0090 E A vs OO O nn 0000000 0000000 OOOOOOO Available switches a XBee shield Serie 1 b XBee shield Serie 2 c External switch Traxster Robot ROS Driver Guide 8 Chapter 2 User Manual 2 1 Testing firmware To test the firmware switch the TraxBot on as refered in section 1 6 1 open the Arduino IDE and then open the serial terminal Serial Monitor a The serial console window will pop up e dev ttyACMO v Y Autoscroll No line ending 19200 baud Attention the baud rate should be define to 19200 baud To perform a linear move with the TraxBot motors as a testing firmware example type in the serial console 9 1 20 1 20e followed by the Enter button e dev ttyACMO 9 1 20 1 20e Send If all the procedure was done correct y the TraxBot will start to move forward in a straight linear motion To stop the motors simply send the command wl le Traxster Robot ROS Driver Guide 10 2 2 Running TraxBot driver in ROS e First run the roscore Master in an Ubuntu console S roscCcore e roscore http chopin 04 11311 File Edit View Search Terminal Help Checking log directory for disk usage This may
11. llation Guide 1 1 Requirements preferences and needs Ubuntu Compatible Installation RER ROS version Distribution Instructions Install ROS according to the Ubuntu version running on your machine and your Ubuntu 10 04 Lucid Lynx ros org wiki fuert 11 10 Oneiric Ocelot e Installation 12 04 Precise Pangolin Ubuntu 10 04 Lucid Lynx http 10 10 Maverick Meerkat 11 04 Natty Narwhal 11 10 Oneiric Ocelot ros org wiki electr ic Installation Released August 30 2011 e Install subversion on Ubuntu open an Ubuntu system console then sudo apt get install subversion Traxster Robot ROS Driver Guide 1 2 ROS files organization For better management of the stacks it is possible to create a folder to use all the stacks which are necessary without having to use in the root folder of stacks of ROS it is necessary to create a folder called stacks in the home folder and add this destination path for ROS be aware of this new location e Create a folder in your home directory to manage all your custom ROS packages and stacks cd msc rails cel stacks e Add the new path to yout bash initilzation file bashrc in your home directory replace USER with your username S echo export ROS PACKAGE PATH home USER stacks ROS PACKAGE PATH gt gt baschrc 1 3 Download and Install the TraxBot driver e Open your stack folder created in section 1 2
12. nav_msgs List the files using sensor_msgs Cameralnfo rosmsg users sensor_msgs Cameralnfo rosrun rosrun allows you to run an executable in an arbitrary package without having to cd or roscd there first Usage rosrun package executable Example Run turtlesim rosrun turtlesim turtlesim_node rosnode Displays debugging information about ROS nodes including publications subscriptions and connections Commands rosnode ping rosnode list rosnode info rosnode machine Test connectivity to node List active nodes Print information about a node List nodes running on a particular ma chine rosnode kill Kills a running node Examples Kill all nodes rosnode kill a List nodes on a machine rosnode machine aqy local Ping all nodes rosnode ping all roslaunch Starts ROS nodes locally and remotely via SSH as well as setting parameters on the parameter server Examples Launch on a different port roslaunch p 1234 package filename launch Launch a file in a package roslaunch package filename launch Launch on the local nodes roslaunch local package filename launch rostopic A tool for displaying debug information about ROS topics including publishers subscribers publishing rate and messages Commands rostopic bw Display bandwidth used by topic rostopic echo Print messages to screen rostopic hz Display publishing rate of topic rostopic list Print information about a
13. ow_s d Short frame 17746 2 video lines were missing last was 76 Warn wide_ste d Some frames were never seen The dropped packet count will be incorrect Warn jwide ste Publishina narrow stereo texturedi left imaae mono Info Inarrow s e gt Severity Fatal Error Ej warn Ej Info E Debug Pause Clear Setup Levels New Window E Enabled Regex From 4 Message Node Location EJ Topics 19 4 o Usage rxconsole tf Command line Tools tf_echo A tool that prints the information about a particular transformation between a source_frame and a target_frame Usage rosrun tf tf_echo lt source_frame gt lt target_frame gt Examples To echo the transform between map and odom rosrun tf tf_echo map odom view_frames A tool for visualizing the full tree of coordinate transforms Usage rosrun tf view_frames evince frames pdf Copyright 2010 Willow Garage
14. pload arduino Double click in TrabotRobot DriverROSv2 ino If these steps were successful you will see the firmware code n the Arduino IDE 0 43 Applications Places System PIM 8 q EN tie 1 GHz ty 4 Fri Jul 13 10 23 mil amp gt e TraxbotRobot_DriverROS_v2 Arduino 1 0 1 File Edit Sketch Tools Help TraxbotRobot_DriverROS_v2 f Arduino libraries include lt EEPROM h gt include lt stdlib h gt include lt Wire h gt include lt string h gt include lt math h gt Traxbot robot amp Omn13MD l b include Traxbot h RobotSerial Communication lib include RobotSerialComm h Omni3MD robot Traxbot traxbot ff Arquments fo r the reply unsigned int reply arq S 4 Arduino Uno on fdevittyaCMO es TraxbotRobot Driver Next connect the USB cable from the computer taking into attention Section 1 6 2 and upload the firmware code as shown in the next figure a 43 Applications Places Syste e TraxbotRobot_DriverROS_v2 File Edit Sketch Tools Help Robot DriverROS v2 You will know when the code was successfully uploaded when you see the confirmation message Done Uploading Traxster Robot ROS Driver Guide 7 1 6 Important Notes AN 1 6 1 Hardware startup Before plugging the USB cable to the Arduino Uno e g code upload or simply sending commands make sure that the traxBot s power switch is ON Otherwise the robot will not respond because the Arduino Uno uses the f

Download Pdf Manuals

image

Related Search

Related Contents

mini-tommy-trimless-qr-c51-manual      C3400 UG PB 59381604 Rev x_x.book  取扱説明書(10/05/12)  GO!NotifyLink pour BlackBerry - Enterprise Server User Guides  The visrock user manual  Siemens OXYMAT 61 man  Meuleuses Kristall  MANUAL DEL OPERADOR QUICKLY  

Copyright © All rights reserved.
Failed to retrieve file