ROS 1 meta-package to get access to the Hovermap online data through a client computer.
The Hovermap API setup requires:
- an Emesent Hovermap with Cortex >= 4.0.2
- a Ubuntu 20.04 LTS environment with ROS 1 Noetic installed (Dockerfile and scripts are provided to generate this if required)
- an Emesent Hovermap accessible via:
- Wi-Fi, or
- a USB-to-Ethernet adaptor, or
- a Hovermap ST Fischer-to-Ethernet interface
-
Power on Hovermap
-
Connect to Hovermap via the Wi-Fi access point; SSID named after the Hovermap serial number (e.g.
st_0001
) -
Enable the external API through the Hovermap Web UI
- Visit http://hover.map on a web browser
- Switch on the "Publish external API messages" option
Note: if the option does not appear you will need to contact Emesent about an updated entitlement file.
-
If you would like to use the external API over ethernet, turn off the "Use Wi-Fi for external API" switch
-
Power cycle Hovermap and verify the external API is enabled by connecting as described below
The API is configured to connect over either Wi-Fi or Ethernet on boot time with one of the following interfaces with their specific configurations:
Interface | ip_prefix | Hovermap address | Client address | Netmask |
---|---|---|---|---|
ST Fischer-to-Ethernet | 192.168.2.0 | 192.168.2.115 | 192.168.2.100 | 255.255.255.0 |
USB-to-Ethernet | 192.168.3.0 | 192.168.3.115 | 192.168.3.100 | 255.255.255.0 |
Wi-Fi | 10.9.0.0 | 10.9.0.1 | 10.9.0.99 | 255.255.255.0 |
-
Connect to the Wi-Fi access point again or plug in the physical connection from your machine to the Hovermap if you are using Ethernet.
-
Set up a network profile with a manual static IP as specified in the "Client address" from the table
-
Check the connection to the Hovermap is setup correctly by pinging Hovermap
ping -c 5 192.168.2.115 # Hovermap address as specified in table above
We provide a Dockerfile and scripts in the docker folder to assist with the image generation and container running.
-
Clone the repository
git clone git@github.com:Emesent/hovermap_ros_api.git
-
Edit the mule.yaml config file to fill out these values for the network interface used for your connection.
mule_network: "your_network_interface" # The client computer's active network interface name ip_prefix: "192.168.2.0" # as in the table ip_netmask: "255.255.255.0" # as in the table
-
Build the Dockerfile and run the container
cd hovermap_ros_api ./docker/build_docker ./docker/run_docker
-
Run the client and Verify the API connection works successfully by checking the rosout and getting this message:
started core service [/rosout] process[hovermap_api_mule-2]: started with pid [239] [INFO] [1689641473.095754]: Delay started (give subscribers time to connect) [INFO] [1689209676.101692]: Delay finished [INFO] [1689209676.609904, 2930.950000]: Added peer st_0001 at tcp://192.168.2.115:{49184,49189} [INFO] [1689209676.613040, 2930.959000]: Connected to st_0001 at tcp://192.168.2.115:49189
On a different shell check the
rostopic list
output is:/cortex/lidar/corrected /cortex/mule_bridge/status /cortex/occupancy_grid_map/configuration /cortex/occupancy_grid_map/data /cortex/odometry /cortex/tf /cortex/tf_static /rosout /rosout_agg
- Start a Mapping mission either on the Web UI or through Commander.
- Once the mission is fully running, check there is data coming through the topics (e.g.
rostopic hz /cortex/occupancy_grid_map/data
).
Topic name | Type | Description | Update Rate (Hz) | Notes |
---|---|---|---|---|
cortex/mule_bridge/status | mule_bridge_msgs/Status | Internal mule status | 1 | in /odom frame |
cortex/lidar/corrected | sensor_msgs/PointCloud2 | SLAM corrected lidar point cloud | 20 | in /odom frame |
cortex/occupancy_grid_map/data | sensor_msgs/PointCloud2 | Occupancy grid for navigation | 1 | 160x160x160 grid; 0.25m resolution by default |
cortex/odometry | nav_msgs/Odometry | SLAM corrected odometry | 100 | |
cortex/tf | tf_msgs/TFMessage | Non-static transform | Variable | |
cortex/tf_static | tf_msgs/TFMessage | Static transforms | Once (latched) |
Topic name | Type | Description |
---|---|---|
cortex/occupancy_grid_map/configuration | std_msgs/String | Occupancy grid config YAML endpoint |
-
Transform tree (
cortex/tf and cortex/tf_static
)- The TF contains the depicted below
- It follows REP 105 convention
hovermap_base
is the external reference point on hovermap and it is located as depicted belowhovermap_base
andbase_link
are coincident when hovermap is attached to an unsupported robotic platformbase_link
referenced the robot reference axis for navigation and control purposes when attached to a supported robotic platform
Tf tree Reference axis -
Odometry (
cortex/odometry
)- Local SLAM corrected odometry from
odom
tohovermap_base
- If global (mission) corrected odometry is required the
map->odom
transform should be applied to theodometry
value - Topic covariance is not populated
- Local SLAM corrected odometry from
-
Occupancy grid (
cortex/occupancy_grid_map/data
)- Fixed size 3D occupancy grid describing local obstacles detected by the Hovermap
- It is meant to be used for navigation purposes only
-
LiDAR corrected point cloud (
cortex/lidar/corrected
)- SLAM corrected LiDAR data with the following packet structure:
POINT_CLOUD_REGISTER_POINT_STRUCT( PointXYZItime, (float, x, x)(float, y, y)(float, z, z) (double, timestamp, timestamp) (float, intensity, intensity) (std::uint8_t, ring, ring) (std::uint8_t, returnNum, returnNum) );
-
Perception configuration (
cortex/occupancy_grid_map/configuration
)- The occupancy grid's parameters can be configured before a mission is launched. See relevant section for details
- The configuration is sent to the Hovermap as a string representing a YAML file. A node is provided to do this.
- The custom configuration is only used when using external_api, and is persistent across runs
The Hovermap is configured to act as an NTP server to allow API users synchronise the client's clock to the Hovermap's by:
- Synchronise the client with the Hovermap by editing
/etc/chrony/chrony.conf
- add
server 192.168.2.115 iburst
- remove/comment any other
server
orpool
directives the file
- add
- Start chrony as a service with
service chrony start
- Check the offset between the clocks with
chronyc tracking
Reference ID : C0A80273 (192.168.2.115)
Stratum : 11
Ref time (UTC) : Wed Jul 12 05:49:04 2023
System time : 0.000000002 seconds slow of NTP time
Last offset : +0.000003220 seconds
RMS offset : 0.000048081 seconds
Frequency : 3.325 ppm slow
Residual freq : +0.001 ppm
Skew : 0.801 ppm
Root delay : 0.000319398 seconds
Root dispersion : 0.002432903 seconds
Update interval : 64.0 seconds
Leap status : Normal
Note : Chrony synchronises clocks by slowly skewing towards the target clock. Consequently a large offset between
clocks may take a while to converge. In this case, run sudo chronyc -a makestep
to force chrony to discontinuously change the time to the server time.
The Hovermap ROS API publishes an occupancy grid that can be configured for your specific application.
Parameter | Type | Description |
---|---|---|
on_hit | int | Voxel value increase on hit |
on_miss | int | Voxel value increase when missed |
occupied_threshold | int | Value above which voxel is considered occupied |
occupied_min | int | Minimum value for voxel |
occupied_max | int | Maximum value for voxel |
voxel_size | float | Side length of an individual voxel in the grid |
dimensions/x | int | Number of voxels in the x axis of the grid |
dimensions/y | int | Number of voxels in the y axis of the grid |
dimensions/z | int | Number of voxels in the z axis of the grid |
The occupancy grid holds unitless occupancy values that represent how likely it is to be occupied.
When a LiDAR point is detected in a voxel, the occupancy is increased by on_hit
. When the LiDAR point
is raycasted to, the occupancy value of the voxels it did not hit is increased by on_miss
.
Above an occupancy value of occupied_threshold
, that voxel is considered occupied for navigation purposes.
The occupancy value is clamped within the [occupied_min
, occupied_max
] range
The parameters chosen, in particular the dimensions and the voxel size, can affect the performance at which the Hovermap's perception system runs.
To ensure nominal performance, the total number of voxels should be less than or equal to 70 million and the voxel_size
should be between 0.05
and 0.25
.
The configuration is persistent between boots, so it only needs to be configured once. Sending an empty config to the Hovermap will reset the configuration to the default.
-
Update the parameters in the
perception_config.yaml
file in the hovermap_api config directory -
Build the hovermap_api package with
catkin build hovermap_api
-
Configure the Hovermap ROS API and ensure connection is established as per the Quick Start instructions
-
Run the perception configuration node with
rosrun hovermap_api configure_perception
-
Start a mapping mission to validate the changes to the occupancy grid
-
Topics on this client are under a
cortex
namespace. Changing or removing it will prevent Cortex from sending/receiving the topic data to/from the Hovermap. Note that the data frame ids do not contain the namespace. -
Sometimes the perception configuration is not set correctly on the first attempt. Running
rosrun hovermap_api configure_perception
twice fixes the issue.