API Details

The following sections outline the details of the ROS1 Noetic API that can be used with OutdoorNav Software.

Platform API

The Platform API provides topics to communicate with the hardware platform (eg. sensor data, command velocity, tfs, etc…). This API can be used by autonomy software packages to interface with the hardware platform.

Topics Published by UGV

The topics in this section are published by the UGV. If available, they are used by the OutdoorNav software.

tf

Message Type: tf2_msgs/TFMessage

Usage: The tf topic represents the relationship between coordinate frames (sensors frame and localization frame). See http://wiki.ros.org/tf for more information.

tf_static

Message Type: tf2_msgs/TFMessage

Usage: This is similar to the necessary tf topic previously described, but it only needs to be published and latched once for transforms that are static and do not change. See http://wiki.ros.org/tf for more information.

<platform>_velocity_controller/odom

Message Type: nav_msgs/Odometry

Usage: This is the odometry provided by the platform control system, usually a velocity controller. Replace <platform> with the name of your robot (ie. jackal/husky/warthog). If a third-party vehicle, then you should have your own ROS odometry topic that is being used as input to OutdoorNav.

extra_imu/imu/data

Message Type: sensor_msgs/Imu

Usage: This is the data published from the IMU. OutdoorNav requires the data published by the gyroscope of the imu for localization. The transform frame in which this topic is published must be available in the tf tree of the UGV, i.e., /tf_static topic.

rtk_heading

Message Type: sensor_msgs/Imu

Usage: Accurate RTK heading published from the dual antenna GPS system on the UGV. Only the yaw information (rotation around z axis) is used by the OutdoorNav localization module. The transform frame in which this topic is published must be available in the tf tree of the UGV, i.e., /tf_static topic.

clock

Message Type: rosgraph_msgs/Clock

Usage: The current time of the ROS system running on the platform. This must be of sufficient frequency, but excessive publishing frequency (greater than 100 Hz) may have an adverse effect.

front/scan

Message Type: sensor_msgs/LaserScan

Usage: The laser scan data from the front 2D lidar, that the OutdoorNav software will use for obstacle detection/avoidance. If only one 2D lidar is on your UGV, then its data will be published to this topic. The OutdoorNav software expects this topics TF to be relative to “front_laser”.

rear/scan

Message Type: sensor_msgs/LaserScan

Usage: The laser scan data from the rear 2D lidar, that the OutdoorNav software will use for obstacle detection/avoidance. This will be published only if a second 2D lidar is on your UGV (ie. one at the front and the other at ther rear). The OutdoorNav software expects this topics TF to be relative to “rear_laser”.

velodyne_points

Message Type: Type: sensor_msgs/PointCloud2

Usage: Pointcloud data published by 3D lidar, that the OutdoorNav software will use for obstacle detection/avoidance. If only one 3D lidar is on your UGV, then its data will be published to this topic. The OutdoorNav software expects this topics TF to be relative to “velodyne”.

rear/velodyne_points

Message Type: Type: sensor_msgs/PointCloud2

Usage: Pointcloud data published by 3D lidar, that the OutdoorNav software will use for obstacle detection/avoidance. This will be published only if a second 2D lidar is on your UGV (ie. one at the front and the other at ther rear). The OutdoorNav software expects this topics TF to be relative to “rear_velodyne”.

microhard_snmp

Message Type: microhard_msg

Usage: If a microhard wireless system is used for wifi communication, this topic can be used to obtain the wifi connection information between the platform and the Base Station (or other connected network). This includes signal strength, transmit power, rssi, etc…

Topics Subscribed to by UGV

The UGV subscribes to the topics in this section.

cmd_vel

Message Type: geometry_msgs/Twist

Usage: This message is produced by OutdoorNav to control the velocity of the platform. It is commonly relayed directly into the UGV’s velocity controller.

Autonomy API

The Autonomy provides some relevant topics and services suitable for controlling and monitoring the robot as it is performing autonomous navigation.

Topics Published by OutdoorNav

The OutdoorNav software publishes to the topics in this section either all the time or while an autonomous navigation missions is running. They can be used to monitor the behaviour of OutdoorNav.

cmd_vel

Message Type: geometry_msgs/Twist

Usage: This message is produced by OutdoorNav to control the velocity of the platform. It is commonly relayed directly into the UGV’s velocity controller.

odometry/filtered_map

Message Type: nav_msgs/Odometry

Usage: OutdoorNav will publish the live position and attitude of the UGV in world frame (named as “map”) on this topic.

estop_status

Message Type: std_msgs/Bool

Usage: OutdoorNav will publish status of the emergency stop system of the platform (if available) on this topic.

robot/desiredAction

Message Type: cpr_gps_navigation_msgs/Safety

Usage: The safety monitoring module of the OutdoorNav system processes data from lidars, lasers and UGV platform and publishes a recommended action for the navigation module that is either “PAUSE” or “CONTINUE”. The purpose of this module is to reinforce safe behaviors of the system by processing different sources independently of the navigation and create recommended actions.

mission_server/desired_path

Message Type: geometry_msgs/PoseArray

Usage: This message contains the initial computed path. If path smoothing is disabled, it will compute straight line point-to-point path to the goal. If path smoothing is enabled, it will compute a dynamically feasible path (according to a turning radius parameter).

mission_server/global_path

Message Type: geometry_msgs/PoseArray

Usage: This message contains the currentpath that the UGV is following. It is initialized with the initial path, but can be modified if new paths are required to perform collision avoidance maneuvers.

current_goal

Message Type: geometry_msgs/PoseStamped

Usage: This topic has the coordination of the current goal tracked by the OutdoorNav system.

missionplan/feedback

Message Type: cpr_gps_navigation_msgs/MissionActionFeedback

Usage: This topic contains the current state machine status of the navigation system. There are 4 possible states: NONE, Execute Path, Replan and Recovery.

missionplan/result

Message Type: cpr_gps_navigation_msgs/MissionActionResult

Usage: OutdoorNav will publish whether execution of navigation mission was successful or not on this topic.

move_base_flex/PathTracker/current_max_velocity

Message Type: geometry_msgs/Twist

Usage: This topic publishes the maximum linear and angular velocities that the path tracker is using at the current iteration.

move_base_flex/PathTracker/lidar_safety

Message Type: geometry_msgs/PolygonStamped

Usage: This topic contains information about the MPC path tracker safety lookahead polygons and can be visualized in RVIZ.

move_base_flex/PathTracker/mpc_local_plan

Message Type: nav_msgs/Path

Usage: This topic contains the local plan currently executed by the MPC.

move_base_flex/PathTracker/path_progress

Message Type: std_msgs/Float32

Usage: Amount of progress of the UGV on the reference toward the goal point.

move_base_flex/PathTracker/plan_spline

Message Type: geometry_msgs/PoseArray

Usage: This topic includes the current reference path being tracked by the path tracker of OutdoorNav. This plan will be show in green in the operator control unit. It can be also viewed in RVIZ.

move_base_flex/SBPLLatticePlanner/plan

Message Type: nav_msgs/Path

Usage: Includes the obstacle free plan produced by the SBPL planner once invoked by the navigation server (when there is obstacle on the path of the UGV).

move_base_flex/global_costmap/costmap

Message Type: nav_msgs/OccupancyGrid

Usage: This is the current dynamic global map costmap around the UGV that is constantly updated using the pointcloud and laser data received by the navigation system. Note that OutdoorNav does not require prior map of the environment. This map can be visualized in RVIZ.

move_base_flex/global_costmap/footprint

Message Type: geometry_msgs/PolygonStamped

Usage: Current footprint of the UGV in the form of a polygon in RVIZ. Visualizable in RVIZ.

move_base_flex/globalplanner/plan

Message Type: nav_msgs/Path

Usage: The raw reference path produced by the UI before being processed by the MPC path tracker.

move_base_flex/local_costmap/costmap

Message Type: nav_msgs/OccupancyGrid

Usage: Current local costmap around the UGV used for obstacle detection. Visualizable in RVIZ.

Topics Subscribed to by OutdoorNav

The OutdoorNav software subscribes to the topics in this section. They can be used to control the behaviour of OutdoorNav.

missionplan/cancel

Message Type: actionlib_msgs/GoalID

Usage: This topic is used to cancel all the missions that have been sent to the OutdoorNav software.

missionplan/goal

Message Type: cpr_gps_navigation_msgs/MissionActionGoal

Usage: This topic is used to send a goal to the OutdoorNav software. The goal can consist of a series of Waypoints and must include a Goal point.

move_base_flex/exe_path/goal

Message Type: mbf_msgs/ExePath

Usage: OutdoorNav can be tasked to follow a given path to the goal using this message. Positions and orientations are defined relative to coordinates in the map frame that OutdoorNav is using. Type of the path tracker to use can be defined here.

move_base_flex/exe_path/cancel

Message Type: std_msgs/Empty

Usage: If OutdoorNav is tracking a goal, the action can be canceled by publishing to this message.

move_base_flex/move_base/goal

Message Type: mbf_msgs/MoveBase

Usage: OutdoorNav can be tasked to track goal using this message and via the legacy “move_base” platform. Positions and orientations are defined relative to coordinates in the map frame that OutdoorNav is using. Type of the path tracker to use can be defined here.

move_base_flex/move_base/cancel

Message Type: std_msgs/Empty

Usage: If OutdoorNav is tracking a goal submitted via the legacy “move_base” format, the action can be canceled by publishing to this message.

robot/desiredAction

Message Type: cpr_gps_navigation_msgs/Safety

Usage: The safety monitoring module of OutdoorNav system processes data from lidars, lasers and UGV platform and publishes a recommended action for the navigation module that is either “PAUSE” or “CONTINUE”. The purpose of this module is to reinforce safe behaviors of the system by processing different sources independently of the navigation and create recommended actions.

Services Exported by OutdoorNav

set_datum

Type: cpr_gps_navigation_msgs/TaskSrv

Usage: This service is used to reset the datum parameters of OutdoorNav running on the UGV. After setting the datum parameter, this service also reinitializes the states of the localization EKFs according to the current sensor readings. If you are sending a mission to the UGV without using the UI and through the API, you must call this service before sending the mission. The TaskSrv request should use the new latitude and the new longitude in the floats[0], floats[1] field , respectively. The ‘strings’ field shold remain empty.

set_pose

Type: robot_localization/SetPose

Usage: This service can be used to reset or reinitialize the EKF filters running on the UGV.

move_base_flex/clear_costmaps

Type: std_srvs/Empty

Usage: This service can be used to clear the navigation costmaps of the UGV if UGV is stuck due to detection of false obstacles by sensors.

Definitions

Message Definitions

cpr_gps_navigation_msgs/AutonomySync

uint8 EMPTY = 0
uint8 PROCESSING = 1
uint8 PENDING_PAUSE = 2
uint8 PAUSED = 3

uint8 IDLE = 4
uint8 TEACH = 5
uint8 REPEAT = 6


# Is the server currently active
uint8 status
uint8[] missionType

cpr_gps_navigation_msgs/Mission

std_msgs/Header header
cpr_gps_navigation_msgs/Waypoint goalpoint
bool set_final_heading
float64 goalpoint_theta
bool set_goal_tolerance
float64 pose_tolerance
float64 yaw_tolerance
cpr_gps_navigation_msgs/Waypoint[] viapoints
cpr_gps_navigation_msgs/Task[] subtasks

cpr_gps_navigation_msgs/MissionAction

#goal definition bool
cpr_gps_navigation_msgs/Mission mission
---
#result definition
string sequence
---
#feedback
string sequence

cpr_gps_navigation_msgs/Safety

string desiredAction

cpr_gps_navigation_msgs/Task

string task_name
string service_call
string version
float64[] floats
string[] strings

cpr_gps_navigation_msgs/Waypoints

float64 x
float64 y

microhard_msg

Header header
string ssid
string wifi_mode
int64 snr
int64 rssi
int64 tx_power
int8 connected_bool
string message

Service Definitions

TaskSrv.srv

string version
float64[] floats
string[] strings
---
bool success

SetPose.srv

geometry_msgs/PoseWithCovarianceStamped pose
---

Standard ROS Services

Advanced Usage

Tasks

Tasks are called after the UGV reaches a mission’s goal point. A Task is a ROS Action call from its specified namespace. An action is a function in a node which can be called remotely, that terminates when a specified goal is reached. This can be used to execute a more complex and useful function at a goal point. Tasks will block the execution of the next mission but can be cancelled while they are in the process of being executed. For instance, if the Task is for the UGV to move its robotics arm to a point and pick up an object, the UGV will remain in place while the Task is being executed, until it has completed or has been cancelled. Once the action is complete, OutdoorNav will resume execution of the next goal in the defined sequence.

Below is an example of a simple task in python which prints the GPS coordinates whenever the Task is called.

from std_srvs.srv import *
from sensor_msgs.msg import NavSatFix
import rospy

lat = None
lon = None

import rospy
import actionlib
from sensor_msgs.msg import NavSatFix
import cpr_gps_navigation_msgs.msg


class RecordGPS(object):
    _result = cpr_gps_navigation_msgs.msg.UITaskResult()
    lat = None
    lon = None

    def __init__(self, name):
        self.sub = rospy.Subscriber("/navsat/upgrade/fix", NavSatFix, self.fix_sub)
        self._action_name = name
        self._as = actionlib.SimpleActionServer(self._action_name, cpr_gps_navigation_msgs.msg.UITaskAction, execute_cb=self.handle_record_gps, auto_start=False)
        self._as.start()

    def handle_record_gps(self, goal):
        rospy.loginfo("Latitude: %f Longtitude: %f"%(self.lat, self.lon))
        with open('goal_point_positions.txt', 'a') as the_file:
           the_file.write("Latitude: %f Longtitude: %f \n"%(self.lat, self.lon))
        the_file.close()
        self._result.success = True
        self._as.set_succeeded(self._result)

    def fix_sub(self, msg):
        self.lat = msg.latitude
        self.lon = msg.longitude


if __name__ == '__main__':
    rospy.init_node('record_gps', anonymous=False)
    OBJ = RecordGPS(rospy.get_name())
    rospy.loginfo('record gps server started.')
    rospy.spin()

Below is another example action task for the UGV to wait at the goal point. This Task is already included in the OutdoorNav software and is available under the /wait namespace.

import rospy
import actionlib
import cpr_gps_navigation_msgs.msg

class Wait(object):
    _result = cpr_gps_navigation_msgs.msg.UITaskResult()
    sleep_time = 0.1

    def __init__(self, name):
        self._action_name = name
        self._as = actionlib.SimpleActionServer(self._action_name, cpr_gps_navigation_msgs.msg.UITaskAction, execute_cb=self.waitCB, auto_start=False)
        self._as.start()

    def waitCB(self, goal):
        success = True
        # num_sleeps_cycles = 10.0/self.sleep_time;
        num_sleeps_cycles = goal.floats[0]/self.sleep_time;
        i = 0;
        while i <= num_sleeps_cycles:
            if self._as.is_preempt_requested():
                success = False
                self._result.success = success
                self._as.set_preempted(self._result)
                break

            rospy.sleep(self.sleep_time);
            i = i+1

        if success:
            self._result.success = success
            self._as.set_succeeded(self._result)


if __name__ == '__main__':
    rospy.init_node('wait', anonymous=False)
    OBJ = Wait(rospy.get_name())
    rospy.loginfo('Wait server started.')
    rospy.spin()

For more information on providing a ROS Action see http://wiki.ros.org/actionlib and http://wiki.ros.org/actionlib/Tutorials.

Examples

Mission Client to Run Navigation

Aside from using the OutdoorNAV Web UI, sending missions to the navigation software can only be done through the API. This can be done by writing a mission client node that creates an action client and connects to the corresponding action server.

Warning

In the case that you are writing your own mission client node, you must ensure that the datum parameter on the UGV and in the mission client python code are exactly the same before sending missions to the navigation server. Failure to properly synchronize this parameter will result in unpredictable behavior of the system.

This example shows how to use the API to send UGV to a goal point passing through two waypoints. The goal is to send the UGV to a mission identical to this yaml file but without the need to generate this file.

# Datum: North: 4816326.036091, East: 536530.798342
- name: Mission 1  # Mission 0
  datum: [536530.7983423516, 4816326.036091047]
  utm_zone: 17T
  goalpoint:
    position: [148.526323131402, 236.3220023885369]  # Point 1
  goalpoint_theta: 30
  viapoints:
        - position: [141.3061444293708, 217.5968263382092]  # Point 2
        - position: [148.703843060066, 203.7562180841342]  # Point 3
  actions:
    []

The following python code shows to how send this mission to the UGV.

#! /usr/bin/env python

from __future__ import print_function

# Brings in the SimpleActionClient
import actionlib

# Brings in the messages used by the fibonacci action, including the
# goal message and the result message.
import rospy
import actionlib_tutorials.msg
import cpr_gps_navigation_msgs.msg
import geometry_msgs.msg
import utm

from robot_localization.srv import SetDatum
from geographic_msgs.msg import GeoPose

def find_utm_coords(lat, lon):
    u = utm.from_latlon(lat, lon)
    east = u[0]
    north = u[1]
    return north, east

def sendGoal():

    # We chose datum at the following location
    datum_lat = 43.498969
    datum_lon = -80.548142

    # This ekf_initial_estimate code block is required if the datum you have chosen is not the same as the one on the UGV
    rospy.wait_for_service('ekfs_initial_estimate', timeout = 2.0)

    try:
        datum_service = rospy.ServiceProxy('ekfs_initial_estimate', SetDatum)
        req = GeoPose()
        req.position.latitude = datum_lat;
        req.position.longitude = datum_lon;
        req.orientation.w = 1.0;
        res = datum_service(req)
        rospy.loginfo("Datum set, sleeping for 2 seconds")
    except rospy.ServiceException, e:
        print("Service call failed")
        return

    # Sleep to make sure datum is set properly and ekfs are converged
    rospy.sleep(2.0)

    # Assume that our goal is to get to the goalpoint (43.5011, -80.5463) through the viapoints (43.5010, -80.5462) and (43.5008, -80.5463)
    datum_north, datum_east = find_utm_coords(datum_lat, datum_lon) #find utm coordinate of the datum

    goalpoint_lat = 43.5011
    goalpoint_lon = -80.5463
    goalpoint_north, goalpoint_east = find_utm_coords(goalpoint_lat, goalpoint_lon) #find utm coordinate of the desired point

    viapoint1_lat = 43.5009
    viapoint1_lon = -80.5464
    viapoint1_north, viapoint1_east = find_utm_coords(viapoint1_lat, viapoint1_lon) #find utm coordinate of the desired point


    viapoint2_lat = 43.5008
    viapoint2_lon = -80.5463
    viapoint2_north, viapoint2_east = find_utm_coords(viapoint2_lat, viapoint2_lon) #find utm coordinate of the desired point


    # Creates a SimpleActionClient, passing the type of the action
    client = actionlib.SimpleActionClient('missionplan', cpr_gps_navigation_msgs.msg.MissionAction)

    # Waits until the action server has started up and started
    # listening for goals.
    if client.wait_for_server(timeout = rospy.Duration(2.0)):

        # Creates a goal to send to the action server.
        goal = cpr_gps_navigation_msgs.msg.MissionGoal()

        goal.mission.header.seq = 1;
        goal.mission.header.stamp = rospy.Time.now();
        goal.mission.header.frame_id = "map";

        goal.mission.goalpoint.x = goalpoint_east - datum_east;
        goal.mission.goalpoint.y = goalpoint_north - datum_north;
        goal.mission.goalpoint_theta = 0.0;

        viapoint1 = cpr_gps_navigation_msgs.msg.Waypoint();
        viapoint1.x = viapoint1_east - datum_east;
        viapoint1.y = viapoint1_north - datum_north;

        viapoint2 = cpr_gps_navigation_msgs.msg.Waypoint();
        viapoint2.x = viapoint2_east - datum_east;
        viapoint2.y = viapoint2_north - datum_north;


        goal.mission.viapoints = [viapoint2, viapoint1];

        # UNCOMMENT IF YOU WANT A FINAL HEADING AT THE GOAL POINT
        # goal.mission.set_final_heading = True
        # goal.mission.goalpoint_theta = 30

        # UNCOMMENT IF YOU WANT A FINAL GOAL TOLERANCE SET AT THE GOAL POINT [m, rad]
        # goal.mission.set_goal_tolerance = True
        # goal.mission.pose_tolerance = 0.1
        # goal.mission.yaw_tolerance = 0.2

        # Sends the goal to the action server.
        client.send_goal(goal)
    else:
        return False;

    # Waits for the server to finish performing the action.
    client.wait_for_result()

    # Prints out the result of executing the action
    return client.get_result()  # A FibonacciResult

if __name__ == '__main__':
    try:
        rospy.init_node('simple_nav_example')
        res = sendGoal()
        if res:
            print("mission completed!")
        else:
            print("mission server is not available!")
    except rospy.ROSInterruptException:
        print("mission server is not avialable")
        pass

Note

The user must make sure that the datum chosen in this python code is the same as the datum parameter on the UGV. Otherwise, the /ekf_initial_estimate service must be called to synchronize the datum on the UGV.