├── .gitignore ├── CHANGELOG.rst ├── CMakeLists.txt ├── README.rst ├── msg ├── FourWheelSteering.msg └── FourWheelSteeringStamped.msg └── package.xml /.gitignore: -------------------------------------------------------------------------------- 1 | *.a 2 | *.o 3 | *.os 4 | *.pyc 5 | *.so 6 | *.tar.gz 7 | *~ 8 | TAGS 9 | build/ 10 | msg_gen/ 11 | src/ 12 | 13 | -------------------------------------------------------------------------------- /CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package four_wheel_steering_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.1.1 (2020-05-13) 6 | ------------------ 7 | * Update maintainer email 8 | * Contributors: Vincent Rousseau 9 | 10 | 1.1.0 (2020-04-06) 11 | ------------------ 12 | * Bump CMake version to avoid CMP0048 warning (`#4 `_) 13 | * Contributors: Alejandro Hernández Cordero 14 | 15 | 1.0.0 (2017-04-26) 16 | ------------------ 17 | * Update url path 18 | * Initial commit from https://github.com/Romea/romea_controllers 19 | * Contributors: Vincent Rousseau 20 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(four_wheel_steering_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS message_generation std_msgs) 5 | # We want boost/format.hpp, which isn't in its own component. 6 | find_package(Boost REQUIRED) 7 | 8 | add_message_files( 9 | DIRECTORY msg 10 | FILES FourWheelSteering.msg FourWheelSteeringStamped.msg) 11 | 12 | generate_messages(DEPENDENCIES std_msgs) 13 | 14 | catkin_package( 15 | CATKIN_DEPENDS message_runtime std_msgs 16 | DEPENDS Boost) 17 | -------------------------------------------------------------------------------- /README.rst: -------------------------------------------------------------------------------- 1 | four_wheel_steering_msgs 2 | ============== 3 | 4 | ROS messages for vehicles using four wheel steering. 5 | -------------------------------------------------------------------------------- /msg/FourWheelSteering.msg: -------------------------------------------------------------------------------- 1 | ## Driving command or odometry msg for a FourWheelSteering vehicle. 2 | # $Id$ 3 | 4 | # Assumes FourWheelSteering with front-wheel and rear-wheel steering. The left 5 | # and right front wheels are generally at different angles. To simplify, 6 | # the commanded angle corresponds to the yaw of a virtual wheel located at the 7 | # center of the front or rear axle, like on a tricycle. Positive yaw is to 8 | # the left. (This is *not* the angle of the steering wheel inside the 9 | # passenger compartment.) 10 | # 11 | # Zero steering angle velocity means change the steering angle as 12 | # quickly as possible. Positive velocity indicates an absolute 13 | # rate of change either left or right. 14 | # 15 | float32 front_steering_angle # position of the virtual angle (radians) 16 | float32 rear_steering_angle # position of the virtual angle (radians) 17 | float32 front_steering_angle_velocity # rate of change (radians/s) 18 | float32 rear_steering_angle_velocity # rate of change (radians/s) 19 | 20 | # Speed, acceleration and jerk (the 1st, 2nd and 3rd 21 | # derivatives of position). All are measured at the vehicle's 22 | # center of the rear axle. 23 | # 24 | # Speed is the scalar magnitude of the velocity vector. 25 | # The speed value is the norm of the velocity component in x (longitudinal) 26 | # and y (lateral) direction 27 | # Direction is forward unless the sign is negative, indicating reverse. 28 | # If the steering angle are equal to +/- pi/2, then the direction is left 29 | # unless the sign is negative, indicating right. 30 | # 31 | # Zero acceleration means change speed as quickly as 32 | # possible. Positive acceleration indicates an absolute 33 | # magnitude; that includes deceleration. 34 | # 35 | # Zero jerk means change acceleration as quickly as possible. Positive 36 | # jerk indicates an absolute rate of acceleration change in 37 | # either direction (increasing or decreasing). 38 | # 39 | float32 speed # forward speed (m/s) 40 | float32 acceleration # acceleration (m/s^2) 41 | float32 jerk # jerk (m/s^3) 42 | -------------------------------------------------------------------------------- /msg/FourWheelSteeringStamped.msg: -------------------------------------------------------------------------------- 1 | ## Time stamped drive command or odometry for robots with FourWheelSteering. 2 | # $Id$ 3 | 4 | Header header 5 | FourWheelSteering data 6 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | four_wheel_steering_msgs 3 | 1.1.1 4 | 5 | ROS messages for robots using FourWheelSteering. 6 | 7 | Vincent Rousseau 8 | Vincent Rousseau 9 | BSD 10 | 11 | http://ros.org/wiki/four_wheel_steering_msgs 12 | https://github.com/ros-drivers/four_wheel_steering_msgs.git 13 | https://github.com/ros-drivers/four_wheel_steering_msgs/issues 14 | 15 | catkin 16 | 17 | message_generation 18 | message_runtime 19 | message_runtime 20 | 21 | std_msgs 22 | 23 | 24 | 25 | 26 | 27 | --------------------------------------------------------------------------------