├── .gitignore ├── msg ├── AckermannDriveStamped.msg └── AckermannDrive.msg ├── mainpage.dox ├── CHANGELOG.rst ├── README.rst ├── CMakeLists.txt ├── package.xml └── LICENSE /.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 | -------------------------------------------------------------------------------- /msg/AckermannDriveStamped.msg: -------------------------------------------------------------------------------- 1 | ## Time stamped drive command for robots with Ackermann steering. 2 | # $Id$ 3 | 4 | std_msgs/Header header 5 | AckermannDrive drive 6 | -------------------------------------------------------------------------------- /mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | Messages for driving a vehicle using Ackermann steering. 6 | 7 | There are no nodes, scripts or other APIs in this package. 8 | 9 | */ 10 | -------------------------------------------------------------------------------- /CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | Change history 2 | ============== 3 | 4 | 2.0.2 (2019-08-28) 5 | ------------------ 6 | * missing std msg dependency 7 | * Contributors: Rousseau Vincent 8 | 9 | 2.0.1 (2019-08-14) 10 | ------------------ 11 | * Initial version for ros2 12 | * Contributors: Marcel Stüttgen 13 | 14 | -------------------------------------------------------------------------------- /README.rst: -------------------------------------------------------------------------------- 1 | ackermann_msgs 2 | ============== 3 | 4 | ROS messages for vehicles using front-wheel `Ackermann steering`_. It 5 | was defined by the ROS `Ackermann steering group`_. 6 | 7 | ROS documentation: http://www.ros.org/wiki/ackermann_msgs 8 | 9 | .. _Ackermann steering: http://en.wikipedia.org/wiki/Ackermann_steering_geometry 10 | .. _Ackermann steering group: http://www.ros.org/wiki/Ackermann%20Group 11 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.15) 2 | 3 | project(ackermann_msgs) 4 | 5 | # Default to C++17 6 | if(NOT CMAKE_CXX_STANDARD) 7 | set(CMAKE_CXX_STANDARD 17) 8 | endif() 9 | 10 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 11 | add_compile_options(-Wall -Wextra -Wpedantic) 12 | endif() 13 | 14 | find_package(ament_cmake REQUIRED) 15 | find_package(rosidl_default_generators REQUIRED) 16 | 17 | find_package(std_msgs REQUIRED) 18 | 19 | rosidl_generate_interfaces(${PROJECT_NAME} 20 | "msg/AckermannDrive.msg" 21 | "msg/AckermannDriveStamped.msg" 22 | DEPENDENCIES std_msgs 23 | ADD_LINTER_TESTS 24 | ) 25 | 26 | ament_export_dependencies(rosidl_default_runtime) 27 | 28 | ament_package() 29 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ackermann_msgs 5 | 2.0.2 6 | ROS2 messages for robots using Ackermann steering. 7 | 8 | Vincent Rousseau 9 | Jack O'Quin 10 | BSD 11 | 12 | ament_cmake 13 | rosidl_default_generators 14 | 15 | std_msgs 16 | 17 | rosidl_default_runtime 18 | std_msgs 19 | 20 | ament_lint_common 21 | 22 | rosidl_interface_packages 23 | 24 | 25 | ament_cmake 26 | 27 | 28 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 2 | 3 | 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 4 | 5 | 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. 6 | 7 | 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. 8 | 9 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 10 | 11 | -------------------------------------------------------------------------------- /msg/AckermannDrive.msg: -------------------------------------------------------------------------------- 1 | ## Driving command for a car-like vehicle using Ackermann steering. 2 | # $Id$ 3 | 4 | # Assumes Ackermann front-wheel steering. The left and right front 5 | # wheels are generally at different angles. To simplify, the commanded 6 | # angle corresponds to the yaw of a virtual wheel located at the 7 | # center of the front 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 a desired absolute 13 | # rate of change either left or right. The controller tries not to 14 | # exceed this limit in either direction, but sometimes it might. 15 | # 16 | float32 steering_angle # desired virtual angle (radians) 17 | float32 steering_angle_velocity # desired rate of change (radians/s) 18 | 19 | # Drive at requested speed, acceleration and jerk (the 1st, 2nd and 20 | # 3rd derivatives of position). All are measured at the vehicle's 21 | # center of rotation, typically the center of the rear axle. The 22 | # controller tries not to exceed these limits in either direction, but 23 | # sometimes it might. 24 | # 25 | # Speed is the desired scalar magnitude of the velocity vector. 26 | # Direction is forward unless the sign is negative, indicating reverse. 27 | # 28 | # Zero acceleration means change speed as quickly as 29 | # possible. Positive acceleration indicates a desired absolute 30 | # magnitude; that includes deceleration. 31 | # 32 | # Zero jerk means change acceleration as quickly as possible. Positive 33 | # jerk indicates a desired absolute rate of acceleration change in 34 | # either direction (increasing or decreasing). 35 | # 36 | float32 speed # desired forward speed (m/s) 37 | float32 acceleration # desired acceleration (m/s^2) 38 | float32 jerk # desired jerk (m/s^3) 39 | --------------------------------------------------------------------------------