include
dataspeed_ulc_can
dispatch.h
Go to the documentation of this file.
1
/*********************************************************************
2
* Software License Agreement (BSD License)
3
*
4
* Copyright (c) 2018, Dataspeed Inc.
5
* All rights reserved.
6
*
7
* Redistribution and use in source and binary forms, with or without
8
* modification, are permitted provided that the following conditions
9
* are met:
10
*
11
* * Redistributions of source code must retain the above copyright
12
* notice, this list of conditions and the following disclaimer.
13
* * Redistributions in binary form must reproduce the above
14
* copyright notice, this list of conditions and the following
15
* disclaimer in the documentation and/or other materials provided
16
* with the distribution.
17
* * Neither the name of Dataspeed Inc. nor the names of its
18
* contributors may be used to endorse or promote products derived
19
* from this software without specific prior written permission.
20
*
21
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32
* POSSIBILITY OF SUCH DAMAGE.
33
*********************************************************************/
34
35
#ifndef _DATASPEED_ULC_CAN_DISPATCH_H
36
#define _DATASPEED_ULC_CAN_DISPATCH_H
37
#include <stdint.h>
38
39
namespace
dataspeed_ulc_can
40
{
41
42
typedef
struct
{
43
int16_t
lon_command
:16;
// speed mode: 0.0025 m/s, -81.920 to 81.915 m/s, +-183 mph
44
// accel mode: 5e-4 m/s^2, -16.384 to 16.3835 m/s^2
45
int16_t
yaw_command
:16;
// yaw rate mode: 0.00025 rad/s, -8.1920 to 8.1915 rad/s
46
// curvature mode: 0.0000061 1/m, -0.1999 1/m to 0.1999 1/m
47
48
uint8_t
steering_mode
:1;
// 0 = yaw rate mode, 1 = curvature mode
49
uint8_t
shift_from_park
:1;
50
uint8_t
enable_shifting
:1;
51
uint8_t
enable_steering
:1;
52
uint8_t
enable_pedals
:1;
53
uint8_t
clear
:1;
54
uint8_t
pedals_mode
:1;
// 0 = speed mode, 1 = accel mode
55
uint8_t
coast_decel
:1;
56
57
uint8_t :8;
58
uint8_t :8;
59
uint8_t
wdc
;
60
}
MsgUlcCmd
;
61
62
typedef
struct
{
63
uint8_t
linear_accel
;
// 0.025 m/s^2, 0 to 6.375 m/s^2
64
uint8_t
linear_decel
;
// 0.025 m/s^2, 0 to 6.375 m/s^2
65
uint8_t
lateral_accel
;
// 0.05 m/s^2, 0 to 12.75 m/s^2
66
uint8_t
angular_accel
;
// 0.02 rad/s^2, 0 to 5.1 rad/s^2
67
uint8_t
jerk_limit_throttle
;
// 0.1 m/s^3, 0 to 25.5 m/s^3
68
uint8_t
jerk_limit_brake
;
// 0.1 m/s^3, 0 to 25.5 m/s^3
69
uint8_t :8;
70
uint8_t
wdc
;
71
}
MsgUlcCfg
;
72
73
typedef
struct
{
74
int16_t
speed_ref
:13;
// 0.02 m/s,
75
uint16_t
timeout
:1;
76
uint16_t
pedals_enabled
:1;
77
uint16_t
pedals_mode
:1;
78
int16_t
speed_meas
:13;
// 0.02 m/s
79
uint16_t
override
:1;
80
uint16_t
steering_enabled
:1;
81
uint16_t
steering_mode
: 1;
82
int8_t
accel_ref
;
// 0.05 m/s^2
83
int8_t
accel_meas
;
// 0.05 m/s^2
84
uint8_t
max_steering_angle
: 7;
// 5 deg
85
uint8_t
coasting
: 1;
86
uint8_t
max_steering_vel
:6;
// 8 deg/s
87
uint8_t
steering_preempted
: 1;
88
uint8_t
speed_preempted
: 1;
89
}
MsgUlcReport
;
90
91
typedef
struct
{
92
uint8_t
module
;
93
uint8_t
platform
;
94
uint16_t
major
;
95
uint16_t
minor
;
96
uint16_t
build
;
97
}
MsgVersion
;
98
99
#define BUILD_ASSERT(cond) do { (void) sizeof(char [1 - 2*!(cond)]); } while(0)
100
static
void
dispatchAssertSizes
() {
101
BUILD_ASSERT
(8 ==
sizeof
(
MsgUlcCmd
));
102
BUILD_ASSERT
(8 ==
sizeof
(
MsgUlcCfg
));
103
BUILD_ASSERT
(8 ==
sizeof
(
MsgUlcReport
));
104
BUILD_ASSERT
(8 ==
sizeof
(
MsgVersion
));
105
}
106
#undef BUILD_ASSERT
107
108
enum
{
109
ID_ULC_CMD
= 0x076,
110
ID_ULC_CONFIG
= 0x077,
111
ID_ULC_REPORT
= 0x078,
112
ID_VERSION
= 0x07F,
113
};
114
115
}
// namespace dataspeed_ulc_can
116
117
#endif // _DATASPEED_ULC_CAN_DISPATCH_H
118
dataspeed_ulc_can::MsgUlcReport::speed_ref
int16_t speed_ref
Definition:
dispatch.h:74
dataspeed_ulc_can::MsgUlcCmd::enable_pedals
uint8_t enable_pedals
Definition:
dispatch.h:52
dataspeed_ulc_can::MsgUlcCmd::shift_from_park
uint8_t shift_from_park
Definition:
dispatch.h:49
dataspeed_ulc_can::MsgUlcCmd::wdc
uint8_t wdc
Definition:
dispatch.h:59
dataspeed_ulc_can::MsgUlcCfg::jerk_limit_throttle
uint8_t jerk_limit_throttle
Definition:
dispatch.h:67
dataspeed_ulc_can::MsgUlcReport::speed_preempted
uint8_t speed_preempted
Definition:
dispatch.h:88
dataspeed_ulc_can::MsgUlcReport::accel_ref
int8_t accel_ref
Definition:
dispatch.h:82
dataspeed_ulc_can::MsgUlcCmd::yaw_command
int16_t yaw_command
Definition:
dispatch.h:45
dataspeed_ulc_can::MsgVersion
Definition:
dispatch.h:91
dataspeed_ulc_can::MsgUlcCfg::wdc
uint8_t wdc
Definition:
dispatch.h:70
dataspeed_ulc_can::MsgUlcCfg::linear_accel
uint8_t linear_accel
Definition:
dispatch.h:63
dataspeed_ulc_can
Definition:
dispatch.h:39
dataspeed_ulc_can::MsgUlcCmd::enable_steering
uint8_t enable_steering
Definition:
dispatch.h:51
dataspeed_ulc_can::MsgUlcCfg::jerk_limit_brake
uint8_t jerk_limit_brake
Definition:
dispatch.h:68
dataspeed_ulc_can::MsgUlcReport::max_steering_vel
uint8_t max_steering_vel
Definition:
dispatch.h:86
dataspeed_ulc_can::MsgUlcCmd::clear
uint8_t clear
Definition:
dispatch.h:53
dataspeed_ulc_can::MsgUlcReport::steering_mode
uint16_t steering_mode
Definition:
dispatch.h:81
dataspeed_ulc_can::MsgUlcReport::steering_enabled
uint16_t steering_enabled
Definition:
dispatch.h:80
dataspeed_ulc_can::MsgUlcCmd::enable_shifting
uint8_t enable_shifting
Definition:
dispatch.h:50
dataspeed_ulc_can::MsgUlcReport::timeout
uint16_t timeout
Definition:
dispatch.h:75
BUILD_ASSERT
#define BUILD_ASSERT(cond)
Definition:
dispatch.h:99
dataspeed_ulc_can::MsgUlcCmd::steering_mode
uint8_t steering_mode
Definition:
dispatch.h:48
dataspeed_ulc_can::MsgVersion::major
uint16_t major
Definition:
dispatch.h:94
dataspeed_ulc_can::MsgVersion::platform
uint8_t platform
Definition:
dispatch.h:93
dataspeed_ulc_can::MsgUlcCfg::lateral_accel
uint8_t lateral_accel
Definition:
dispatch.h:65
dataspeed_ulc_can::MsgUlcCmd::coast_decel
uint8_t coast_decel
Definition:
dispatch.h:55
dataspeed_ulc_can::MsgVersion::module
uint8_t module
Definition:
dispatch.h:92
dataspeed_ulc_can::MsgUlcCmd::lon_command
int16_t lon_command
Definition:
dispatch.h:43
dataspeed_ulc_can::MsgUlcReport::steering_preempted
uint8_t steering_preempted
Definition:
dispatch.h:87
dataspeed_ulc_can::MsgUlcCmd
Definition:
dispatch.h:42
dataspeed_ulc_can::MsgUlcCfg::linear_decel
uint8_t linear_decel
Definition:
dispatch.h:64
dataspeed_ulc_can::MsgUlcReport::accel_meas
int8_t accel_meas
Definition:
dispatch.h:83
dataspeed_ulc_can::MsgUlcCfg::angular_accel
uint8_t angular_accel
Definition:
dispatch.h:66
dataspeed_ulc_can::MsgUlcReport::speed_meas
int16_t speed_meas
Definition:
dispatch.h:78
dataspeed_ulc_can::MsgUlcReport::max_steering_angle
uint8_t max_steering_angle
Definition:
dispatch.h:84
dataspeed_ulc_can::ID_ULC_CONFIG
Definition:
dispatch.h:110
dataspeed_ulc_can::ID_VERSION
Definition:
dispatch.h:112
dataspeed_ulc_can::MsgUlcCfg
Definition:
dispatch.h:62
dataspeed_ulc_can::MsgUlcReport::coasting
uint8_t coasting
Definition:
dispatch.h:85
dataspeed_ulc_can::MsgUlcReport::override
uint16_t override
Definition:
dispatch.h:79
dataspeed_ulc_can::ID_ULC_CMD
Definition:
dispatch.h:109
dataspeed_ulc_can::MsgUlcReport::pedals_enabled
uint16_t pedals_enabled
Definition:
dispatch.h:76
dataspeed_ulc_can::MsgVersion::minor
uint16_t minor
Definition:
dispatch.h:95
dataspeed_ulc_can::ID_ULC_REPORT
Definition:
dispatch.h:111
dataspeed_ulc_can::dispatchAssertSizes
static void dispatchAssertSizes()
Definition:
dispatch.h:100
dataspeed_ulc_can::MsgVersion::build
uint16_t build
Definition:
dispatch.h:96
dataspeed_ulc_can::MsgUlcReport
Definition:
dispatch.h:73
dataspeed_ulc_can::MsgUlcCmd::pedals_mode
uint8_t pedals_mode
Definition:
dispatch.h:54
dataspeed_ulc_can::MsgUlcReport::pedals_mode
uint16_t pedals_mode
Definition:
dispatch.h:77
dataspeed_ulc_can
Author(s): Micho Radovnikovich
autogenerated on Fri Dec 2 2022 03:20:37