Skip to content
Snippets Groups Projects
Commit 5ea78b5f authored by Dherbomez Gérald's avatar Dherbomez Gérald
Browse files

[FEAT] add ROS2 msg for CAN bus

parents
No related branches found
No related tags found
No related merge requests found
Showing with 196 additions and 0 deletions
cmake_minimum_required(VERSION 3.5)
project(can_zoe_msgs)
# Default to C99
if(NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 99)
endif()
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
find_package(geometry_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(std_msgs REQUIRED)
install(
FILES my_bridge.yaml
DESTINATION share/${PROJECT_NAME})
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/Frame.msg"
"msg/Speed.msg"
"msg/Odom.msg"
"msg/IMU.msg"
"msg/Steering.msg"
"msg/CmdAcceleration.msg"
"msg/CmdBrake.msg"
"msg/CmdSteering.msg"
"msg/SteeringCmdInfo.msg"
"msg/CmdPRND.msg"
"msg/CmdOptions.msg"
"msg/PRNDCmdInfo.msg"
"msg/ActivationCondition.msg"
"msg/RobotizationActivation.msg"
"msg/SpeedControl.msg"
"msg/BattInfo.msg"
"msg/TorqueInfo.msg"
"msg/SelectorAInfo.msg"
"msg/SelectorBInfo.msg"
DEPENDENCIES geometry_msgs builtin_interfaces std_msgs# Add packages that above messages depend on, in this case geometry_msgs for Sphere.msg
)
ament_package()
# Activation of the robotization conditions
std_msgs/Header header # Header
uint8 vehicle # Vehicle conditions [0,1] (0 "valid - valid general condition" 1 "invalid - invalid general condition")
uint8 door_fl # Front left door [0,1] (0 "valid - closed door" 1 "invalid - opened door")
uint8 door_fr # Front right door [0,1] (0 "valid - closed door" 1 "invalid - opened door")
uint8 door_rl # Rear left door [0,1] (0 "valid - closed door" 1 "invalid - opened door")
uint8 door_rr # Rear right door [0,1] (0 "valid - closed door" 1 "invalid - opened door")
uint8 door_r # Rear hatch [0,1] (0 "valid - closed door" 1 "invalid - opened door")
uint8 prnd # PRND (Park, Reverse, Neutral, Drive) position [0,1] (0 "valid - valid PRND position" 1 "invalid - invalid PRND position")
uint8 handbrake # Handbrake position [0,1] (0 "valid - handbrake released" 1 "invalid - handbrake applied")
uint8 emergency_stop # Emergency stop [0,1] (0 "valid - emergency stop disabled" 1 "invalid - emergency stop enabled")
uint8 driver_safety # Driver safety [0,1] (0 "valid" 1 "invalid")
uint8 passenger_safety # Passengers safety [0,1] (0 "valid" 1 "invalid")
uint8 can_intersys # CAN intersystem [0,1] (0 "valid" 1 "invalid")
std_msgs/Header header
float32 voltage
float32 soc
int32 autonomie_km
int32 autonomie_kwh
# Acceleration command
std_msgs/Header header # Header
float32 acceleration # Acceleration command [0...6553.5] (0...100%)
bool can_publish # true or false
# Brake command
std_msgs/Header header # Header
float32 deceleration # Deceleration command [0...6553.5] (0...100%)
bool can_publish # true or false
std_msgs/Header header # Header
uint8 clignotant_gauche # left blinker 0 or 1
uint8 clignotant_droit # right blinker 0 or 1
uint8 clignotant_warning # warning 0 or 1
uint8 feux_veilleuse # lighting 0 or 1
uint8 feux_code # road lighting 0 or 1
uint8 feux_route # road lighting 0 or 1
uint8 feux_antibrouillard_av # Front A-F 0 or 1
uint8 feux_antibrouillard_ar # Rear A-F 0 or 1
uint8 klaxon # Horn 0 or 1
# PRND command
std_msgs/Header header # Header
uint8 prnd # PRND (Park, Reverse, Neutral, Drive) command [0...3] (0:P, 1:R, 2:N, 3:D)
# Steering wheel command
std_msgs/Header header # Header
float32 angle # Steering wheel angle [-720...5833.5 °]
float32 rotation_speed # Steering wheel rotation speed [0...6553.5 °/s]
uint8 cooperative_mode # Cooperative mode reactivation [0,1]
bool can_publish # true or false
std_msgs/Header header
uint32 id
bool is_rtr
bool is_extended
bool is_error
uint8 dlc
uint8[8] data
# Inertial Measurement Unit of the ESP
std_msgs/Header header # Header
float32 acc_lon # Longitudinal acceleration [-10...2.75 m/s2]
float32 acc_lat # Lateral acceleration [-131.072...131.068 g]
float32 yaw_rate # Yaw rate [-204.8...204.7 °/s]
# Odometry
std_msgs/Header header # Header
float32 odom_fl # Front left Wheel tops [0...65535 top] (1top/cm)
float32 odom_fr # Front right Wheel tops [0...65535 top] (1top/cm)
float32 odom_rl # Rear left Wheel tops [0...65535 top] (1top/cm)
float32 odom_rr # Rear right Wheel tops [0...65535 top] (1top/cm)
# PRND command Info
std_msgs/Header header # Header
uint8 prnd_enable # PRND (Park, Reverse, Neutral, Drive) enable [0...7] (3 "PRND-Neutre" 4 "PRND-D" 2 "PRND-R" 1 "PRND-Park")
uint8 mode_auto # Current auto mode [0...3] (0 "manual_mode" 1 "robotized_mode" 2 "cooperative_mode" 3 "driver_selector_mode")
uint8 counter_id # Counter Id reactivation [0...15]
# Robotization activation flags
std_msgs/Header header # header
uint8 mode_auto # Desired auto mode [0...3] (0 "manual_mode" 1 "robotized_mode" 2 "cooperative_mode" 3 "driver_selector_mode")
uint8 steering # Activation of the EPS (Electronic Power Steering) command through the robotized CAN [0,1]
uint8 acceleration # Activation of the acceleration command through the robotized CAN [0,1]
uint8 brake # Activation of the brake command through the robotized CAN [0,1]
uint8 prnd # Activation of the PRND (Park, Reverse, Neutral, Drive) command through the robotized CAN [0,1]
uint8 checksum_id # Checksum ID [0...15 CRC]
uint8 counter_id # Counter ID [0...15]
std_msgs/Header header
uint8 brake_led
uint8 accel_led
uint8 emergency_stop_a
uint8 buzzer_accel_brake
std_msgs/Header header
uint8 mode
uint8 inter_dae
uint8 inter_accel
uint8 inter_brake
uint8 led_dae
uint8 led_default
uint8 emergency_stop_b
uint8 buzzer_dae
# Wheels speed
std_msgs/Header header # Header
float32 wheel_speed_fl # Front left Wheel speed [0...2047.5 rpm]
float32 wheel_speed_fr # Front right Wheel speed [0...2047.5 rpm]
float32 wheel_speed_rl # Rear left Wheel speed [0...2047.5 rpm]
float32 wheel_speed_rr # Rear right Wheel speed [0...2047.5 rpm]
float32 speed # Vehicle speed [0...655.35 km/h]
std_msgs/Header header
float32 desired_speed
float32 current_speed
# Steering wheel
std_msgs/Header header # Header
float32 angle # Steering wheel angle [-3276.8...3276.7 °]
float32 angle_offset # Steering wheel angle offset [-3276.8...3276.7 °]
float32 rotation_speed # Steering wheel rotation speed [-3276.8...3276.7 °/s]
# Steering wheel command info
std_msgs/Header header # Header
float32 angle # Steering wheel angle [-720...5833.5 °]
float32 angle_error # Steering wheel angle error [-720...64815.0 °]
float32 torque_measured # Measured steering wheel torque [-200...209.5 N/m]
float32 torque_generated # Generated steering wheel torque [-200...209.5 N/m]
uint8 mode_auto # Current auto mode [0...3] (0 "manual_mode" 1 "robotized_mode" 2 "cooperative_mode" 3 "driver_selector_mode")
uint8 counter_id # Counter Id reactivation [0...15]
std_msgs/Header header
float32 meanefftorque
float32 requestedtorqueafterproc
float32 elecbrakewheelstorquerequest
float32 driverbrakewheeltq_req
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment