ros2_rover
Loading...
Searching...
No Matches
lx16a_consts.hpp
Go to the documentation of this file.
1// MIT License
2
3// Copyright (c) 2023 Miguel Ángel González Santamarta
4
5// Permission is hereby granted, free of charge, to any person obtaining a copy
6// of this software and associated documentation files (the "Software"), to deal
7// in the Software without restriction, including without limitation the rights
8// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9// copies of the Software, and to permit persons to whom the Software is
10// furnished to do so, subject to the following conditions:
11
12// The above copyright notice and this permission notice shall be included in
13// all copies or substantial portions of the Software.
14
15// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21// SOFTWARE.
22
23#ifndef LX16A_CONSTS_HPP
24#define LX16A_CONSTS_HPP
25
26#include <cstdint>
27
28namespace lx16a {
29
30constexpr uint8_t SERVO_ID_ALL = 0xfe;
31constexpr uint8_t SERVO_FRAME_HEADER = 0x55;
32
33// CMDS
34constexpr uint8_t SERVO_MOVE_TIME_WRITE = 1;
35constexpr uint8_t SERVO_MOVE_TIME_READ = 2;
36constexpr uint8_t SERVO_MOVE_TIME_WAIT_WRITE = 7;
37constexpr uint8_t SERVO_MOVE_TIME_WAIT_READ = 8;
38constexpr uint8_t SERVO_MOVE_START = 11;
39constexpr uint8_t SERVO_MOVE_STOP = 12;
40constexpr uint8_t SERVO_ID_WRITE = 13;
41constexpr uint8_t SERVO_ID_READ = 14;
42constexpr uint8_t SERVO_ANGLE_OFFSET_ADJUST = 17;
43constexpr uint8_t SERVO_ANGLE_OFFSET_WRITE = 18;
44constexpr uint8_t SERVO_ANGLE_OFFSET_READ = 19;
45constexpr uint8_t SERVO_ANGLE_LIMIT_WRITE = 20;
46constexpr uint8_t SERVO_ANGLE_LIMIT_READ = 21;
47constexpr uint8_t SERVO_VIN_LIMIT_WRITE = 22;
48constexpr uint8_t SERVO_VIN_LIMIT_READ = 23;
49constexpr uint8_t SERVO_TEMP_MAX_LIMIT_WRITE = 24;
50constexpr uint8_t SERVO_TEMP_MAX_LIMIT_READ = 25;
51constexpr uint8_t SERVO_TEMP_READ = 26;
52constexpr uint8_t SERVO_VIN_READ = 27;
53constexpr uint8_t SERVO_POS_READ = 28;
54constexpr uint8_t SERVO_OR_MOTOR_MODE_WRITE = 29;
55constexpr uint8_t SERVO_OR_MOTOR_MODE_READ = 30;
56constexpr uint8_t SERVO_LOAD_OR_UNLOAD_WRITE = 31;
57constexpr uint8_t SERVO_LOAD_OR_UNLOAD_READ = 32;
58constexpr uint8_t SERVO_LED_CTRL_WRITE = 33;
59constexpr uint8_t SERVO_LED_CTRL_READ = 34;
60constexpr uint8_t SERVO_LED_ERROR_WRITE = 35;
61constexpr uint8_t SERVO_LED_ERROR_READ = 36;
62
63// ERRORS
64constexpr uint8_t SERVO_ERROR_OVER_TEMPERATURE = 1;
65constexpr uint8_t SERVO_ERROR_OVER_VOLTAGE = 2;
66constexpr uint8_t SERVO_ERROR_LOCKED_ROTOR = 4;
67
68// SERVOS
69constexpr uint8_t MOTOR_LEFT_FRONT = 1;
70constexpr uint8_t MOTOR_LEFT_MIDDLE = 2;
71constexpr uint8_t MOTOR_LEFT_BACK = 3;
72constexpr uint8_t MOTOR_RIGHT_FRONT = 4;
73constexpr uint8_t MOTOR_RIGHT_MIDDLE = 5;
74constexpr uint8_t MOTOR_RIGHT_BACK = 6;
75
76constexpr uint8_t SERVO_LEFT_FRONT = 7;
77constexpr uint8_t SERVO_RIGHT_FRONT = 8;
78constexpr uint8_t SERVO_LEFT_BACK = 9;
79constexpr uint8_t SERVO_RIGHT_BACK = 10;
80
81} // namespace lx16a
82#endif
Definition lx16a.hpp:35
constexpr uint8_t SERVO_VIN_READ
Definition lx16a_consts.hpp:52
constexpr uint8_t SERVO_RIGHT_FRONT
Definition lx16a_consts.hpp:77
constexpr uint8_t SERVO_LEFT_BACK
Definition lx16a_consts.hpp:78
constexpr uint8_t SERVO_OR_MOTOR_MODE_WRITE
Definition lx16a_consts.hpp:54
constexpr uint8_t SERVO_ERROR_OVER_VOLTAGE
Definition lx16a_consts.hpp:65
constexpr uint8_t SERVO_ANGLE_OFFSET_ADJUST
Definition lx16a_consts.hpp:42
constexpr uint8_t SERVO_ANGLE_LIMIT_READ
Definition lx16a_consts.hpp:46
constexpr uint8_t MOTOR_LEFT_BACK
Definition lx16a_consts.hpp:71
constexpr uint8_t SERVO_ID_WRITE
Definition lx16a_consts.hpp:40
constexpr uint8_t SERVO_TEMP_MAX_LIMIT_READ
Definition lx16a_consts.hpp:50
constexpr uint8_t SERVO_ANGLE_LIMIT_WRITE
Definition lx16a_consts.hpp:45
constexpr uint8_t SERVO_MOVE_TIME_WAIT_WRITE
Definition lx16a_consts.hpp:36
constexpr uint8_t SERVO_MOVE_TIME_WRITE
Definition lx16a_consts.hpp:34
constexpr uint8_t SERVO_RIGHT_BACK
Definition lx16a_consts.hpp:79
constexpr uint8_t SERVO_MOVE_START
Definition lx16a_consts.hpp:38
constexpr uint8_t SERVO_FRAME_HEADER
Definition lx16a_consts.hpp:31
constexpr uint8_t SERVO_ID_ALL
Definition lx16a_consts.hpp:30
constexpr uint8_t MOTOR_RIGHT_FRONT
Definition lx16a_consts.hpp:72
constexpr uint8_t SERVO_TEMP_READ
Definition lx16a_consts.hpp:51
constexpr uint8_t MOTOR_RIGHT_BACK
Definition lx16a_consts.hpp:74
constexpr uint8_t MOTOR_LEFT_MIDDLE
Definition lx16a_consts.hpp:70
constexpr uint8_t MOTOR_RIGHT_MIDDLE
Definition lx16a_consts.hpp:73
constexpr uint8_t SERVO_LED_CTRL_WRITE
Definition lx16a_consts.hpp:58
constexpr uint8_t SERVO_TEMP_MAX_LIMIT_WRITE
Definition lx16a_consts.hpp:49
constexpr uint8_t SERVO_VIN_LIMIT_READ
Definition lx16a_consts.hpp:48
constexpr uint8_t SERVO_MOVE_STOP
Definition lx16a_consts.hpp:39
constexpr uint8_t SERVO_ERROR_OVER_TEMPERATURE
Definition lx16a_consts.hpp:64
constexpr uint8_t SERVO_LED_CTRL_READ
Definition lx16a_consts.hpp:59
constexpr uint8_t SERVO_ERROR_LOCKED_ROTOR
Definition lx16a_consts.hpp:66
constexpr uint8_t SERVO_MOVE_TIME_WAIT_READ
Definition lx16a_consts.hpp:37
constexpr uint8_t SERVO_ANGLE_OFFSET_WRITE
Definition lx16a_consts.hpp:43
constexpr uint8_t MOTOR_LEFT_FRONT
Definition lx16a_consts.hpp:69
constexpr uint8_t SERVO_LED_ERROR_WRITE
Definition lx16a_consts.hpp:60
constexpr uint8_t SERVO_MOVE_TIME_READ
Definition lx16a_consts.hpp:35
constexpr uint8_t SERVO_LOAD_OR_UNLOAD_WRITE
Definition lx16a_consts.hpp:56
constexpr uint8_t SERVO_OR_MOTOR_MODE_READ
Definition lx16a_consts.hpp:55
constexpr uint8_t SERVO_ID_READ
Definition lx16a_consts.hpp:41
constexpr uint8_t SERVO_LEFT_FRONT
Definition lx16a_consts.hpp:76
constexpr uint8_t SERVO_LOAD_OR_UNLOAD_READ
Definition lx16a_consts.hpp:57
constexpr uint8_t SERVO_POS_READ
Definition lx16a_consts.hpp:53
constexpr uint8_t SERVO_ANGLE_OFFSET_READ
Definition lx16a_consts.hpp:44
constexpr uint8_t SERVO_LED_ERROR_READ
Definition lx16a_consts.hpp:61
constexpr uint8_t SERVO_VIN_LIMIT_WRITE
Definition lx16a_consts.hpp:47