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

[FEAT] add ROS messages for CAN bus

parents
No related branches found
No related tags found
No related merge requests found
cmake_minimum_required(VERSION 3.0.2)
project(can_zoe_msgs)
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_CXX_STANDARD 14)
endif()
find_package(catkin REQUIRED
COMPONENTS
message_generation
std_msgs
)
add_message_files(DIRECTORY msg
FILES
Frame.msg
Speed.msg
Odom.msg
IMU.msg
Steering.msg
CmdAcceleration.msg
CmdBrake.msg
CmdSteering.msg
SteeringCmdInfo.msg
CmdPRND.msg
CmdOptions.msg
PRNDCmdInfo.msg
ActivationCondition.msg
RobotizationActivation.msg
SpeedControl.msg
BattInfo.msg
TorqueInfo.msg
SelectorAInfo.msg
SelectorBInfo.msg
)
generate_messages(
DEPENDENCIES
std_msgs
)
catkin_package(
CATKIN_DEPENDS
message_runtime
std_msgs
)
# can_zoe_msgs
Package ROS1 that contain ros messages use to communicate with the CAN bus of the Zoe1.
## Message List
| **Name** | **Use** |
|:----------------------:|:-----------------------------------------------------:|
| ActivationCondition | Check the condition of robotization |
| BattInfo | Battery information |
| CmdAcceleration | Order of Acceleration |
| CmdBrake | Order of Braking |
| CmdOptions | Order to control the blinker,light and horn |
| CmdPRND | Order for the gearbox |
| Frame | CAN message |
| IMU | IMU sensor message |
| Odom | Odom sensor message |
| PRNDCmdInfo | gear box information |
| RobotizationActivation | state of control activation |
| SelectorAInfo | state of controlpannel Led and buzzer |
| SelectorBInfo | state of switch led and buzzer on the controlpannel |
| Speed | Speed information |
| SpeedControl | Order for speed control |
| Steering | Steering informtion |
| SteeringCmdInfo | Steering control information |
| TorqueInfo | Torque information |
# Import messages
## Python
```python
from can_zoe_msgs.msg import CmdSteering
from can_zoe_msgs.msg import CmdAcceleration
from can_zoe_msgs.msg import CmdBrake
from can_zoe_msgs.msg import Speed
from can_zoe_msgs.msg import Steering
if __name__ == '__main__':
#var init
acc = CmdAcceleration()
acc.can_publish = True
brk = CmdBrake()
brk.can_publish = True
steer = CmdSteering()
steer.can_publish = True
steer.cooperative_mode = 0
steer.rotation_speed = 100.0
```
## C++
```cpp
#include "can_zoe_msgs/CmdAcceleration.h"
#include "can_zoe_msgs/CmdBrake.h"
#include "can_zoe_msgs/CmdSteering.h"
#include "can_zoe_msgs/CmdPRND.h"
#include "can_zoe_msgs/SpeedControl.h"
int main (){
can_zoe_msgs::CmdAcceleration cmdAccel;
can_zoe_msgs::CmdBrake cmdBrake;
cmdAccel.acceleration = 0.0;
}
}
```
# Activation of the robotization conditions
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")
Header Header
float32 voltage
float32 soc
int32 autonomie_km
int32 autonomie_kwh
\ No newline at end of file
# Acceleration command
Header header # Header
float32 acceleration # Acceleration command [0...6553.5] (0...100%)
bool can_publish # true or false
# Brake command
Header header # Header
float32 deceleration # Deceleration command [0...6553.5] (0...100%)
bool can_publish # true or false
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
Header header # Header
uint8 prnd # PRND (Park, Reverse, Neutral, Drive) command [0...3] (0:P, 1:R, 2:N, 3:D)
# Steering wheel command
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
Header header
uint32 id
bool is_rtr
bool is_extended
bool is_error
uint8 dlc
uint8[8] data
\ No newline at end of file
# Inertial Measurement Unit of the ESP
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
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
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
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]
Header header
uint8 brake_led
uint8 accel_led
uint8 emergency_stop_a
uint8 buzzer_accel_brake
\ No newline at end of file
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
\ No newline at end of file
# Wheels speed
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]
Header header
float32 desired_speed
float32 current_speed
\ No newline at end of file
# Steering wheel
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
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]
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment