Ground Rover with Mavros

原文链接: https://pixhawk.org/dev/ros/ground_rover


This tutorial will show how to use the pixhawk to control a ground rover via ROS.

Environment

  • Ubuntu 12.04 / 14.04
  • ROS Hydro / Indigo

Hardware

  • Pixhawk Autopilot
  • Axialracing AX10 Ridgecrest

Helpful Literature

  • ROS Indigo install guide
  • Pixhawk toolchain installation Linux
  • Building and flashing the Pixhawk
  • General wiring information
  • FTDI wiring for debug console on Serial4/5
  • FTDI wiring for serial communication on TELEM2
  • Mavros Wiki
  • Mavros Offboard Control
  • Pixhawk Circuit Breakers

Setup

Car Setup

  • connect the steering servo to Main Out 3 and the thrust controller to Main Out 4 of the pixhawk

Pixhawk Setup

  • connect the pixhawk via USB and install latest  firmware (branch: master), either via QGroundControl (latest dev version) or by compiling and flashing it yourself
  • In QGroundcontrol, set the Onboard Parameters SYS_AUTOSTART to 50001 and SYS_COMPANION to 921600. This will auto-load the rover config for the pixhawk and enable Mavlink on TELEM2 with 921600 Baud.
  • for communcication with ROS use a dedicated  FTDI connection to TELEM2 port of the pixhawk

A connection via USB could work as well, but for several reasons it is definetely recommended to use serial FTDI connection

  • (optional) use a second  FTDI connection to Seria4/5 for a NuttShell access (e.g. for debugging)
  • (optional) customize the mavlink data stream on TELEM2 by placing the file /etc/extras.txt on the SD-Card (the standard stream will work fine too!)

example for extras.txt:

usleep 100000
#start mavlink custom stream on telem2 (/dev/ttyS2 internally) with 921600 and ftp enabled (-x)
mavlink start -m custom -d /dev/ttyS2 -b 921600 -x
usleep 100000
mavlink stream -d /dev/ttyS2 -s HEARTBEAT -r 5
usleep 100000
mavlink stream -d /dev/ttyS2 -s STATUSTEXT -r 1
usleep 100000
mavlink stream -d /dev/ttyS2 -s SYS_STATUS -r 1
usleep 100000
mavlink stream -d /dev/ttyS2 -s PARAM_VALUE -r 200
usleep 100000
mavlink stream -d /dev/ttyS2 -s HIGHRES_IMU -r 50
usleep 100000
mavlink stream -d /dev/ttyS2 -s ATTITUDE -r 50
usleep 100000
mavlink stream -d /dev/ttyS2 -s ATTITUDE_QUATERNION -r 50
usleep 100000
mavlink stream -d /dev/ttyS2 -s VFR_HUD -r 10
usleep 100000
mavlink stream -d /dev/ttyS2 -s GPS_RAW_INT -r 5
usleep 100000
mavlink stream -d /dev/ttyS2 -s GLOBAL_POSITION_INT -r 5
usleep 100000
mavlink stream -d /dev/ttyS2 -s LOCAL_POSITION_NED -r 5

Some streams (e.g. GPS) are only availabe of the corresponding hardware is connected!

ROS Setup

  • install  Mavros

Step-by-Step Walkthrough

Starting Mavros

Make sure you have read https://pixhawk.org/dev/ros/mavros_offboard at this point!

  • edit px4.launch or create your own launchfile and change the url parameter to the FTDI device that is connected to TELEM2, in my case /dev/ttyUSB0:921600
roslaunch mavros px4.launch
  • check if the connection works! e.g. rostopic echo /mavros/imu/data or /mavros/state

Some topics (e.g. GPS, Vision) will only be available if the hardware is available AND the corresponding mavlink data stream is enabled. If you don't receive any data on any topic at all, double-check your wiring first (the wirings for TELEM2 and Serial4/5 are different e.g.!!)

  • Congratulations, the data connection works!

Sending actuator controls

In this tutorial we will use the mavros actuator_control plugin to send direct servo commands to the FCU for steering and throttle.

  • Setup a ROS node that will permanently publish data to /mavros/actuator_controls using mavros:ActuatorControl message

example for a simple ros publisher:

/*
Copyright Marcel Stüttgen 2015 
simple ros node that will publish ActuatorControl message to /mavros/actuator_controls
*/
#include 
#include 
int main(int argc, char *argv[])
{
    ros::init(argc, argv, "actuator_controls_publisher");
    ros::NodeHandle nh;
    ros::Publisher actuator_controls_pub = nh.advertise<mavros::ActuatorControl>("/mavros/actuator_controls", 1000);
    ros::Rate loop_rate(10);
    double ros_roll;
    double ros_pitch;
    double ros_yaw;
    double ros_throttle;
    while (ros::ok())
    {
        mavros::ActuatorControl actuator_control_msg;
        nh.param<double>("ros_roll", ros_roll, 0.0);
        nh.param<double>("ros_pitch", ros_pitch, 0.0);
        nh.param<double>("ros_yaw", ros_yaw, 0.0);
        nh.param<double>("ros_throttle", ros_throttle, 0.0);
        /*send to control group 0:
        0:roll
        1:pitch
        2:yaw
        3:throttle
        4:flaps
        5:spoilers
        6:airbrakes
        7:landing gear
        see https://pixhawk.ethz.ch/mavlink/#SET_ACTUATOR_CONTROL_TARGET
        and https://pixhawk.org/dev/mixing
        */
        actuator_control_msg.header.stamp = ros::Time::now();
        actuator_control_msg.group_mix = 0;
        actuator_control_msg.controls[0] = ros_roll;
        actuator_control_msg.controls[1] = ros_pitch;
        actuator_control_msg.controls[2] = ros_yaw;
        actuator_control_msg.controls[3] = ros_throttle;
        actuator_control_msg.controls[4] = 0.0;
        actuator_control_msg.controls[5] = 0.0;
        actuator_control_msg.controls[6] = 0.0;
        actuator_control_msg.controls[7] = 0.0;
        actuator_controls_pub.publish(actuator_control_msg);
        ros::spinOnce();
        loop_rate.sleep();
    }
    return 0;
}
  • set the pixhawk to “OFFBOARD-Mode”
rosrun mavros mavsys mode -c OFFBOARD

Pixhawk will reject Offboard Mode, if there is no data published on the actuator control topic! Further more, if the publishing of the data is stopped during Offboard Mode, the Pixhawk will enter failsafe mode

  • arm the servos
rosrun mavros mavsafety arm

Pixhawk might reject arming, e.g. because airspeed sensor is missing or voltage check fails.

See  Pixhawk Circuit Breakers on how to disable the checks. Disabling safety features might be dangerous and is at own risk!

  • if the vehicle is armed, you may now set the ros_params used in the publisher code to values between [-1:1]. If you are using the tutorial code:

throttle:

rosparam set ros_throttle [-1:1]

steering:

rosparam set ros_yaw [-1:1]
  • Video (testing mavros)
src="https://www.youtube.com/embed/ck5iRiQwsC4" height="540" width="810" class="vshare__none" allowfullscreen="" frameborder="0" scrolling="no">

* Video (first autonomous drive with ROS move_base)

src="https://www.youtube.com/embed/M16-pXsDzcU" height="540" width="810" class="vshare__none" allowfullscreen="" frameborder="0" scrolling="no">

* Video (autonomous driving in our laboratory with move_base and sbpl_lattice planner)


你可能感兴趣的:(ROS,Pixhawk,mavlink)