ros2_rover
Loading...
Searching...
No Matches
lx16a.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_HPP
24#define LX16A_HPP
25
26#include <cstdint>
27#include <memory>
28#include <mutex>
29#include <string>
30#include <vector>
31
33#include "lx16a/serial.hpp"
34
35namespace lx16a {
36
37class LX16A {
38private:
39 std::unique_ptr<Serial> serial;
40 std::unique_ptr<std::mutex> mtx;
41
42 void send_command(uint8_t servo_id, uint8_t command,
43 std::vector<uint8_t> params);
44 std::vector<uint8_t> wait_for_response(uint8_t servo_id, uint8_t command);
45 std::vector<uint8_t> query(uint8_t servo_id, uint8_t command);
46
47public:
48 LX16A(std::string serial_port, unsigned int baud_rate);
49
50 uint8_t lower_byte(int value);
51 uint8_t higher_byte(int value);
52 uint8_t word(int low, int high);
53 int clamp(int range_min, int range_max, int value);
54
55 uint8_t get_servo_id(uint8_t servo_id);
56 void set_servo_id(uint8_t servo_id, uint8_t new_servo_id);
57
58 void move(uint8_t servo_id, int position, int time = 0);
59 void move_prepare(uint8_t servo_id, int position, int time = 0);
60 void move_start(uint8_t servo_id = SERVO_ID_ALL);
61 void move_stop(uint8_t servo_id = SERVO_ID_ALL);
62
63 std::vector<uint8_t> get_prepared_move(uint8_t servo_id);
64 int get_position_offset(uint8_t servo_id);
65 std::vector<uint8_t> get_position_limits(int8_t servo_id);
66 int get_position(uint8_t servo_id);
67
68 void set_position_offset(uint8_t servo_id, int deviation);
69 void save_position_offset(uint8_t servo_id);
70 void set_position_limits(uint8_t servo_id, int min_position,
71 int max_position);
72
73 std::vector<uint8_t> get_voltage_limits(uint8_t servo_id);
74 uint8_t get_voltage(uint8_t servo_id);
75 void set_voltage_limits(uint8_t servo_id, int min_voltage, int max_voltage);
76
77 uint8_t get_max_temperature_limit(uint8_t servo_id);
78 uint8_t get_temperature(uint8_t servo_id);
79 void set_max_temperature_limit(uint8_t servo_id, int max_temperature);
80
81 uint8_t get_mode(uint8_t servo_id);
82 int get_motor_speed(uint8_t servo_id);
83 void set_servo_mode(uint8_t servo_id);
84 void set_motor_mode(uint8_t servo_id, int speed = 0);
85 bool is_motor_on(uint8_t servo_id);
86 void motor_on(uint8_t servo_id);
87 void motor_off(uint8_t servo_id);
88
89 bool is_led_on(uint8_t servo_id);
90 void led_on(uint8_t servo_id);
91 void led_off(uint8_t servo_id);
92 uint8_t get_led_errors(uint8_t servo_id);
93 void set_led_errors(uint8_t servo_id, uint8_t error);
94};
95
96} // namespace lx16a
97#endif
int get_motor_speed(uint8_t servo_id)
Definition lx16a.cpp:321
std::unique_ptr< Serial > serial
Definition lx16a.hpp:39
std::vector< uint8_t > get_prepared_move(uint8_t servo_id)
Definition lx16a.cpp:205
std::vector< uint8_t > query(uint8_t servo_id, uint8_t command)
Definition lx16a.cpp:152
uint8_t lower_byte(int value)
Definition lx16a.cpp:159
std::unique_ptr< std::mutex > mtx
Definition lx16a.hpp:40
LX16A(std::string serial_port, unsigned int baud_rate)
Definition lx16a.cpp:36
uint8_t get_servo_id(uint8_t servo_id)
Definition lx16a.cpp:167
std::vector< uint8_t > get_position_limits(int8_t servo_id)
Definition lx16a.cpp:226
void set_position_limits(uint8_t servo_id, int min_position, int max_position)
Definition lx16a.cpp:259
void move(uint8_t servo_id, int position, int time=0)
Definition lx16a.cpp:177
void move_prepare(uint8_t servo_id, int position, int time=0)
Definition lx16a.cpp:187
void move_stop(uint8_t servo_id=SERVO_ID_ALL)
Definition lx16a.cpp:201
void set_voltage_limits(uint8_t servo_id, int min_voltage, int max_voltage)
Definition lx16a.cpp:285
int clamp(int range_min, int range_max, int value)
Definition lx16a.cpp:162
uint8_t get_temperature(uint8_t servo_id)
Definition lx16a.cpp:303
uint8_t get_max_temperature_limit(uint8_t servo_id)
Definition lx16a.cpp:297
void set_max_temperature_limit(uint8_t servo_id, int max_temperature)
Definition lx16a.cpp:308
void send_command(uint8_t servo_id, uint8_t command, std::vector< uint8_t > params)
Definition lx16a.cpp:43
uint8_t word(int low, int high)
Definition lx16a.cpp:161
void led_off(uint8_t servo_id)
Definition lx16a.cpp:375
std::vector< uint8_t > wait_for_response(uint8_t servo_id, uint8_t command)
Definition lx16a.cpp:73
void led_on(uint8_t servo_id)
Definition lx16a.cpp:371
void set_motor_mode(uint8_t servo_id, int speed=0)
Definition lx16a.cpp:340
void set_position_offset(uint8_t servo_id, int deviation)
Definition lx16a.cpp:243
void motor_off(uint8_t servo_id)
Definition lx16a.cpp:361
void set_servo_id(uint8_t servo_id, uint8_t new_servo_id)
Definition lx16a.cpp:172
bool is_motor_on(uint8_t servo_id)
Definition lx16a.cpp:351
int get_position_offset(uint8_t servo_id)
Definition lx16a.cpp:214
std::vector< uint8_t > get_voltage_limits(uint8_t servo_id)
Definition lx16a.cpp:272
uint8_t get_led_errors(uint8_t servo_id)
Definition lx16a.cpp:379
uint8_t higher_byte(int value)
Definition lx16a.cpp:160
bool is_led_on(uint8_t servo_id)
Definition lx16a.cpp:366
void save_position_offset(uint8_t servo_id)
Definition lx16a.cpp:255
void move_start(uint8_t servo_id=SERVO_ID_ALL)
Definition lx16a.cpp:197
uint8_t get_voltage(uint8_t servo_id)
Definition lx16a.cpp:279
void set_led_errors(uint8_t servo_id, uint8_t error)
Definition lx16a.cpp:384
int get_position(uint8_t servo_id)
Definition lx16a.cpp:233
uint8_t get_mode(uint8_t servo_id)
Definition lx16a.cpp:315
void set_servo_mode(uint8_t servo_id)
Definition lx16a.cpp:336
void motor_on(uint8_t servo_id)
Definition lx16a.cpp:357
Definition lx16a.hpp:35
constexpr uint8_t SERVO_ID_ALL
Definition lx16a_consts.hpp:30