Only released in EOL distros:  

Package Summary

The p3dx_hal_vrep package

Overview

Hardware Abstraction Layer (HAL) is specific part of whole p3dx testing robot platform. It creates bridge between topics published by V-REP and ROS environment. It carries out task of translating raw data from simulator into standard timestamped messages of ROS. It also includes time synchronization. This package should be used with model of Pioneer3dx from our V-rep repository.

Architecture

For more information about whole experimental robot stack and ideas behind HAL please see our repo.

Dependencies

Packages

p3dx_urdf_model

This package must be included in ROS workspace prior to generate urdf model of robot and publishing tf tree.

vrep_common

Clock server make use of message type from package "vrep_common". This package is also useful for service type of communication with V-rep environment.

Installation and compilation
  1. Link folder "{V-rep installation folder}/programming/ros_packages/vrep_common" to your ROS workspace folder "{ROS workspace folder}/src".
  2. Run "catkin_make" in terminal.

Nodes

clockServer

This node synchronize time between V-rep simulation time and ROS time. It publish messages from special V-rep's topic "/vrep/info" into ROS dedicated clock topic "/clock". V-rep topic publish special custom type of messages therefore it is needed to build vrep_common messages. More in Dependencies section.

Subscribed Topics

/vrep/info (vrep_common/VrepInfo)
  • publish clock time

Published Topics

/clock (rosgraph_msgs/Clock)

accelerometer

Reads data from V-rep accelerometer sensor and publish it to ROS ecosystem

Subscribed Topics

/vrep/i0_Pioneer_p3dx_Accelerometer (std_msgs/String)
  • reads accelerometer data from vrep

Published Topics

sensor0/axis_data (geometry_msgs/Vector3Stamped)
  • publish stamped vector of accelerations in format [X axis ,Y axis ,Z axis]

gyroscope

Reads data from V-rep gyroscope sensor and publish it to ROS ecosystem

Subscribed Topics

/vrep/i0_Pioneer_p3dx_GyroSensor (std_msgs/String)
  • reads accelerometer data from vrep

Published Topics

sensor0/axis_data (geometry_msgs/Vector3Stamped)
  • publish stamped vector of angular velocities around each axis in format [X axis ,Y axis ,Z axis]

bumper

Reads data from all V-rep bumper sensor and publish it to ROS ecosystem. It uses parameter "vrep_index" to identify certain robot.

Subscribed Topics

/vrep/i0_Pioneer_p3dx_bumper0 (std_msgs/Int32)
  • subscribed topic is dynamically generated. Part i0 is generated as parameter vrep_index substitution in form i[vrep_index]_Pioneer_p3dx_bumper[ID of sensor]

Published Topics

sensor0/Range (sensor_msgs/Range)
  • for each bumper sensor is created publisher in form sensor[ID of sensor]/Range

ultrasonic

Reads data from all V-rep bumper sensor and publish it to ROS ecosystem. It uses parameter "vrep_index" to identify certain robot.

Subscribed Topics

/vrep/i0_Pioneer_p3dx_ultrasonicSensor0 (std_msgs/Float32)
  • subscribed topic is dynamically generated. Part i0 is generated as parameter vrep_index substitution in form i[vrep_index]_Pioneer_p3dx_bumper[ID of sensor]

Published Topics

sensor0/Range (sensor_msgs/Range)
  • for each ultrasonic sensor is created publisher in form sensor[ID of sensor]/Range

laser

It uses parameter "vrep_index" to identify certain robot.

Subscribed Topics

/vrep/i0_Pioneer_p3dx_laserScanner (sensor_msgs/LaserScan)
  • subscribed topic is dynamically generated. Part i0 is generated as parameter vrep_index substitution in form i[vrep_index]_Pioneer_p3dx_laserScanner

Published Topics

sensor0/LaserScan (sensor_msgs/LaserScan)
  • publish the laser scan received from V-rep.

rightMotor

This node makes both way communication for right motor. It receives wheel velocity on topic setVel and sends it to V-rep topic /vrep/i0_Pioneer_p3dx_leftMotor/setVel. In other direction it receives Joint state from V-rep and publish it to getState topic in ROS. It uses parameter "vrep_index" to identify certain robot.

Subscribed Topics

/vrep/i0_Pioneer_p3dx_rightMotor/getState (sensor_msgs/JointState)
  • subscribed topic is dynamically generated. Part i0 is generated as parameter vrep_index substitution in form i[vrep_index]_Pioneer_p3dx_leftMotor.
setVel (std_msgs/Float64)
  • publish angular velocity for left wheel to V-rep.

Published Topics

getState (sensor_msgs/JointState)
/vrep/i0_Pioneer_p3dx_rightMotor/setVel (std_msgs/Float64)

leftMotor

This node makes both way communication for left motor. It receives wheel velocity on topic setVel and sends it to V-rep topic /vrep/i0_Pioneer_p3dx_leftMotor/setVel. In other direction it receives Joint state from V-rep and publish it to getState topic in ROS. It uses parameter "vrep_index" to identify certain robot.

Subscribed Topics

/vrep/i0_Pioneer_p3dx_leftMotor/getState (sensor_msgs/JointState)
  • subscribed topic is dynamically generated. Part i0 is generated as parameter vrep_index substitution in form i[vrep_index]_Pioneer_p3dx_leftMotor.
setVel (std_msgs/Float64)
  • publish angular velocity for left wheel to V-rep.

Published Topics

getState (sensor_msgs/JointState)
/vrep/i0_Pioneer_p3dx_leftMotor/setVel (std_msgs/Float64)

Parameters

Dynamically resolved

These parameters are resolved from node_handle namespace up in launch file hierarchy ending in global namespace. First found occurrence of parameter is taken.

vrep_index

In case of multiple same robots in V-rep environment simulator automatically adds unique ID's to new instances of same object. Sensor scripts in model repository publish unique topics for each sensor and each robot. This parameter is robot's number in V-rep.

tf_prefix

Published messages to ROS use tf_prefixes to prefix frame_id's in messages. Example:[tf_prefix]/base_link.

Global

/use_sim_time

This parameter must be set true when using time synchronization with clockServer.

Wiki: p3dx_hal_vrep (last edited 2015-04-28 14:19:13 by LukasJelinek)