major update to repo structure

This commit is contained in:
Ruixiang Du
2020-10-23 10:44:15 +08:00
parent f981dc4f36
commit 1bfa475ac0
5253 changed files with 302 additions and 757923 deletions

View File

@@ -1,53 +0,0 @@
/*
* async_can.hpp
*
* Created on: Sep 10, 2020 13:22
* Description:
*
* Note: CAN TX is not buffered and only the latest frame will be transmitted.
* Buffered transmission will need to be added if a message has to be divided
* into multiple frames and in applications where no frame should be dropped.
*
* Copyright (c) 2020 Ruixiang Du (rdu)
*/
#ifndef ASYNC_CAN_HPP
#define ASYNC_CAN_HPP
#include <linux/can.h>
#include <memory>
#include "asio/posix/basic_stream_descriptor.hpp"
#include "wrp_sdk/asyncio/async_listener.hpp"
namespace westonrobot {
class AsyncCAN : public AsyncListener,
public std::enable_shared_from_this<AsyncCAN> {
public:
using ReceiveCallback = std::function<void(can_frame *rx_frame)>;
public:
AsyncCAN(std::string can_port = "can0");
void StopService() override;
void SetReceiveCallback(ReceiveCallback cb) { rcv_cb_ = cb; }
void SendFrame(const can_frame &frame);
private:
int can_fd_;
asio::posix::basic_stream_descriptor<> socketcan_stream_;
struct can_frame rcv_frame_;
ReceiveCallback rcv_cb_ = nullptr;
bool SetupPort();
void DefaultReceiveCallback(can_frame *rx_frame);
void ReadFromPort(struct can_frame &rec_frame,
asio::posix::basic_stream_descriptor<> &stream);
};
} // namespace westonrobot
#endif /* ASYNC_CAN_HPP */

View File

@@ -1,56 +0,0 @@
/*
* async_listener.hpp
*
* Created on: Sep 10, 2020 11:50
* Description:
*
* Copyright (c) 2020 Ruixiang Du (rdu)
*/
#ifndef ASYNC_LISTENER_HPP
#define ASYNC_LISTENER_HPP
#include <thread>
#include <mutex>
#include <functional>
#include <iostream>
#include "asio.hpp"
namespace westonrobot {
class AsyncListener {
public:
AsyncListener(std::string port) : port_(port) {}
virtual ~AsyncListener(){};
// do not allow copy
AsyncListener() = delete;
AsyncListener(const AsyncListener& other) = delete;
virtual bool IsOpened() const { return port_opened_; }
bool StartListening() {
if (SetupPort()) {
io_thread_ = std::thread([this]() { io_context_.run(); });
return true;
}
std::cerr << "Failed to setup port, please check if specified port exits "
"or if you have proper permissions to access it"
<< std::endl;
return false;
};
virtual void StopService() {}
protected:
std::string port_;
bool port_opened_ = false;
asio::io_context io_context_;
std::thread io_thread_;
virtual bool SetupPort() = 0;
};
} // namespace westonrobot
#endif /* ASYNC_LISTENER_HPP */

View File

@@ -1,65 +0,0 @@
/*
* async_serial.hpp
*
* Created on: Sep 10, 2020 12:59
* Description:
*
* Copyright (c) 2020 Ruixiang Du (rdu)
*/
#ifndef ASYNC_SERIAL_HPP
#define ASYNC_SERIAL_HPP
#include <cstdint>
#include <memory>
#include <array>
#include <mutex>
#include "wrp_sdk/asyncio/async_listener.hpp"
#include "wrp_sdk/asyncio/ring_buffer.hpp"
namespace westonrobot {
class AsyncSerial : public AsyncListener,
public std::enable_shared_from_this<AsyncSerial> {
public:
using ReceiveCallback =
std::function<void(uint8_t *data, const size_t bufsize, size_t len)>;
public:
AsyncSerial(std::string port_name, uint32_t baud_rate = 115200);
void StopService() override;
bool IsOpened() const override { return serial_port_.is_open(); }
void SetReceiveCallback(ReceiveCallback cb) { rcv_cb_ = cb; }
void SendBytes(const uint8_t *bytes, size_t length);
void SetBaudRate(unsigned baudrate);
void SetHardwareFlowControl(bool enabled) { hwflow_ = enabled; }
private:
asio::serial_port serial_port_;
uint32_t baud_rate_ = 115200;
bool hwflow_ = false;
ReceiveCallback rcv_cb_ = nullptr;
// tx/rx buffering
static constexpr uint32_t rxtx_buffer_size = 1024 * 8;
// rx buffer
std::array<uint8_t, rxtx_buffer_size> rx_buf_;
// tx buffer
uint8_t tx_buf_[rxtx_buffer_size];
RingBuffer<uint8_t, rxtx_buffer_size> tx_rbuf_;
std::recursive_mutex tx_mutex_;
bool tx_in_progress_ = false;
bool SetupPort();
void DefaultReceiveCallback(uint8_t *data, const size_t bufsize, size_t len);
void ReadFromPort();
void WriteToPort(bool check_if_busy);
};
} // namespace westonrobot
#endif /* ASYNC_SERIAL_HPP */

View File

@@ -1,137 +0,0 @@
/*
* ring_buffer.hpp
*
* Created on: Dec 08, 2019 22:22
* Description:
*
* Requirements:
* 1. Size of buffer must be a power of 2
* 2. Maximum buffer size is 2^(number_of_bits_of(size_t)-1)
*
* Implementation details:
*
* - Initial state (empty)
* [0][1][2][3]...[N]
* ^
* R/W
*
* - Add one element
* [D][1][2][3]...[N]
* ^ ^
* R W
*
* - Buffer gets full when last element X is inserted
* [X][D][D][D]...[D]
* ^
* W/R (W>R)
*
* - Buffer data overwritten by new element Y after getting full
* [X][Y][D][D]...[D]
* ^
* W/R (W>R)
*
* Reference:
* [1] https://embeddedartistry.com/blog/2017/05/17/creating-a-circular-buffer-in-c-and-c/
* [2] https://stackoverflow.com/questions/10527581/why-must-a-ring-buffer-size-be-a-power-of-2
* [3] https://stackoverflow.com/questions/9718116/improving-c-circular-buffer-efficiency
* [4] https://www.snellman.net/blog/archive/2016-12-13-ring-buffers/
* [5] tttp://www.trytoprogram.com/c-examples/c-program-to-test-if-a-number-is-a-power-of-2/
*
* Copyright (c) 2019 Ruixiang Du (rdu)
*/
#ifndef RING_BUFFER_HPP
#define RING_BUFFER_HPP
#include <cstdint>
#include <cstddef>
#include <array>
namespace westonrobot {
template <typename T = uint8_t, std::size_t N = 1024>
class RingBuffer {
public:
// Init and reset of buffer
RingBuffer() {
// assert size is a power of 2
static_assert((N != 0) && ((N & (N - 1)) == 0),
"Size of ring buffer has to be 2^n, where n is a positive integer");
size_ = N;
size_mask_ = size_ - 1;
write_index_ = 0;
read_index_ = 0;
}
void Reset() {
write_index_ = 0;
read_index_ = 0;
}
// Buffer size information
bool IsEmpty() { return (read_index_ == write_index_); }
bool IsFull() { return (size_ == GetOccupiedSize()); }
std::size_t GetFreeSize() const { return (size_ - GetOccupiedSize()); }
std::size_t GetOccupiedSize() const { return (write_index_ - read_index_); };
std::array<T, N> GetBuffer() const { return buffer_; }
// Read/Write functions
std::size_t Read(T data[], std::size_t btr) {
for (int i = 0; i < btr; ++i) {
if (ReadByte(&data[i]) == 0) return i;
}
return btr;
}
std::size_t Peek(T data[], std::size_t btp) {
for (int i = 0; i < btp; ++i) {
if (PeekByteAt(&data[i], i) == 0) return i;
}
return btp;
}
std::size_t Write(const T new_data[], std::size_t btw) {
for (int i = 0; i < btw; ++i) {
if (WriteByte(new_data[i]) == 0) return i;
}
return btw;
}
void PrintBuffer() const {
std::cout << "read index: " << read_index_
<< " , write index: " << write_index_ << std::endl;
std::cout << "buffer content: " << std::endl;
for (int i = 0; i < N; ++i)
std::cout << "[" << i << "]"
<< " " << static_cast<int>(buffer_[i]) << std::endl;
}
private:
std::array<T, N> buffer_; // buffer memory to store data
std::size_t size_; // size of allocated memory area
std::size_t size_mask_; // for internal indexing management
std::size_t write_index_; // place new data to be written
std::size_t read_index_; // place earliest written data to be read from
size_t ReadByte(T *data) {
if (IsEmpty()) return 0;
*data = buffer_[read_index_++ & size_mask_];
return 1;
}
size_t PeekByteAt(T *data, size_t n) {
if (n >= GetOccupiedSize()) return 0;
*data = buffer_[(read_index_ + n) & size_mask_];
return 1;
}
size_t WriteByte(const T &new_data) {
if (GetOccupiedSize() == size_) return 0;
buffer_[(write_index_++) & size_mask_] = new_data;
return 1;
}
};
} // namespace westonrobot
#endif /* RING_BUFFER_HPP */

View File

@@ -1,82 +0,0 @@
/*
* mobile_base.hpp
*
* Created on: Jun 17, 2020 11:23
* Description:
*
* Generic mobile base: this class handles the communication
* logic that is similar across different mobile platforms
*
* Copyright (c) 2020 Ruixiang Du (rdu)
*/
#ifndef MOBILE_BASE_HPP
#define MOBILE_BASE_HPP
#include <string>
#include <cstdint>
#include <thread>
#include <mutex>
#include "wrp_sdk/asyncio/async_can.hpp"
#include "wrp_sdk/asyncio/async_serial.hpp"
namespace westonrobot {
class MobileBase {
public:
MobileBase() = default;
virtual ~MobileBase();
// do not allow copy or assignment
MobileBase(const MobileBase &hunter) = delete;
MobileBase &operator=(const MobileBase &hunter) = delete;
void SetCmdTimeout(bool enable, uint32_t timeout_ms = 100);
// connect to roboot from CAN or serial
void Connect(std::string dev_name, int32_t baud_rate = 0);
// disconnect from roboot, only valid for serial port
void Disconnect();
// cmd thread runs at 100Hz (10ms) by default
void SetCmdThreadPeriodMs(int32_t period_ms) {
cmd_thread_period_ms_ = period_ms;
};
protected:
// communication interface
bool can_connected_ = false;
bool serial_connected_ = false;
std::shared_ptr<AsyncCAN> can_if_;
std::shared_ptr<AsyncSerial> serial_if_;
// timeout to be implemented in each vehicle
bool enable_timeout_ = true;
uint32_t timeout_ms_ = 500;
uint32_t watchdog_counter_ = 0;
void FeedCmdTimeoutWatchdog() { watchdog_counter_ = 0; };
// command thread
std::thread cmd_thread_;
int32_t cmd_thread_period_ms_ = 10;
bool cmd_thread_started_ = false;
// internal functions
void ConfigureCAN(const std::string &can_if_name = "can0");
void ConfigureSerial(const std::string uart_name = "/dev/ttyUSB0",
int32_t baud_rate = 115200);
void StartCmdThread();
void ControlLoop(int32_t period_ms);
// functions that must/may be implemented by child classes
virtual void SendRobotCmd() = 0;
virtual void ParseCANFrame(can_frame *rx_frame){};
virtual void ParseUARTBuffer(uint8_t *buf, const size_t bufsize,
size_t bytes_received){};
};
} // namespace westonrobot
#endif /* MOBILE_BASE_HPP */

View File

@@ -1,61 +0,0 @@
/*
* hunter_base.hpp
*
* Created on: Apr 01, 2020 09:43
* Description:
*
* Copyright (c) 2019 Ruixiang Du (rdu)
*/
#ifndef HUNTER_BASE_HPP
#define HUNTER_BASE_HPP
#include <string>
#include <cstdint>
#include <thread>
#include <mutex>
#include "wrp_sdk/platforms/common/mobile_base.hpp"
#include "wrp_sdk/platforms/hunter/hunter_protocol.h"
#include "wrp_sdk/platforms/hunter/hunter_can_parser.h"
#include "wrp_sdk/platforms/hunter/hunter_types.hpp"
namespace westonrobot {
class HunterBase : public MobileBase {
public:
HunterBase() : MobileBase(){};
~HunterBase() = default;
// get robot state
HunterState GetHunterState();
// motion control
void SetMotionCommand(double linear_vel, double steering_angle,
HunterMotionCmd::FaultClearFlag fault_clr_flag =
HunterMotionCmd::FaultClearFlag::NO_FAULT);
private:
// cmd/status update related variables
std::mutex hunter_state_mutex_;
std::mutex motion_cmd_mutex_;
HunterState hunter_state_;
HunterMotionCmd current_motion_cmd_;
// internal functions
void SendRobotCmd() override;
void ParseCANFrame(can_frame *rx_frame) override;
void ParseUARTBuffer(uint8_t *buf, const size_t bufsize,
size_t bytes_received) override{};
void SendMotionCmd(uint8_t count);
void NewStatusMsgReceivedCallback(const HunterMessage &msg);
public:
static void UpdateHunterState(const HunterMessage &status_msg,
HunterState &state);
};
} // namespace westonrobot
#endif /* HUNTER_BASE_HPP */

View File

@@ -1,42 +0,0 @@
/*
* hunter_can_parser.h
*
* Created on: Jan 02, 2020 12:36
* Description:
*
* Copyright (c) 2019 Ruixiang Du (rdu)
*/
#ifndef HUNTER_CAN_PARSER_H
#define HUNTER_CAN_PARSER_H
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
#include "wrp_sdk/platforms/hunter/hunter_protocol.h"
#ifdef __linux__
#include <linux/can.h>
#else
struct can_frame
{
uint32_t can_id;
uint8_t can_dlc;
uint8_t data[8]__attribute__((aligned(8)));
};
#endif
bool DecodeHunterMsgFromCAN(const struct can_frame *rx_frame, HunterMessage *msg);
void EncodeHunterMsgToCAN(const HunterMessage *msg, struct can_frame *tx_frame);
uint8_t CalcHunterCANChecksum(uint16_t id, uint8_t *data, uint8_t dlc);
#ifdef __cplusplus
}
#endif
#endif /* HUNTER_CAN_PARSER_H */

View File

@@ -1,257 +0,0 @@
/*
* hunter_protocol.h
*
* Created on: Jan 02, 2020 12:06
* Description:
*
* Copyright (c) 2019 Ruixiang Du (rdu)
*/
#ifndef HUNTER_PROTOCOL_H
#define HUNTER_PROTOCOL_H
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#define HUNTER_CMD_BUF_LEN 32
#define HUNTER_STATUS_BUF_LEN 32
#define HUNTER_FRAME_SIZE 13
#define HUNTER_MOTOR1_ID ((uint8_t)0x00)
#define HUNTER_MOTOR2_ID ((uint8_t)0x01)
#define HUNTER_MOTOR3_ID ((uint8_t)0x02)
// CAN Definitions
#define CAN_MSG_MOTION_CMD_ID ((uint32_t)0x130)
#define CAN_MSG_MOTION_STATUS_ID ((uint32_t)0x131)
#define CAN_MSG_CONFIG_CMD_ID ((uint32_t)0x210)
#define CAN_MSG_CONFIG_STATUS_ID ((uint32_t)0x211)
#define CAN_MSG_SYSTEM_STATUS_STATUS_ID ((uint32_t)0x151)
#define CAN_MSG_MOTOR1_DRIVER_STATUS_ID ((uint32_t)0x201)
#define CAN_MSG_MOTOR2_DRIVER_STATUS_ID ((uint32_t)0x202)
#define CAN_MSG_MOTOR3_DRIVER_STATUS_ID ((uint32_t)0x203)
/*--------------------- Control/State Constants ------------------------*/
// Motion Control
#define CTRL_MODE_REMOTE ((uint8_t)0x00)
#define CTRL_MODE_CMD_CAN ((uint8_t)0x01)
#define CTRL_MODE_CMD_UART ((uint8_t)0x02)
#define CTRL_MODE_COMMANDED ((uint8_t)0x03)
#define FAULT_CLR_NONE ((uint8_t)0x00)
#define FAULT_CLR_BAT_UNDER_VOL ((uint8_t)0x01)
#define FAULT_CLR_BAT_OVER_VOL ((uint8_t)0x02)
#define FAULT_CLR_MOTOR1_COMM ((uint8_t)0x03)
#define FAULT_CLR_MOTOR2_COMM ((uint8_t)0x04)
#define FAULT_CLR_MOTOR3_COMM ((uint8_t)0x05)
#define FAULT_CLR_MOTOR4_COMM ((uint8_t)0x06)
#define FAULT_CLR_MOTOR_DRV_OVERHEAT ((uint8_t)0x07)
#define FAULT_CLR_MOTOR_OVERCURRENT ((uint8_t)0x08)
// System Configuration
#define STEERING_ZERO_CONFIG_FAIL ((uint8_t)0x00)
#define STEERING_ZERO_CONFIG_SUCCESS ((uint8_t)0xaa)
// System Status Feedback
#define BASE_STATE_NORMAL ((uint8_t)0x00)
#define BASE_STATE_ESTOP ((uint8_t)0x01)
#define BASE_STATE_EXCEPTION ((uint8_t)0x02)
#define FAULT_CAN_CHECKSUM_ERROR ((uint16_t)0x0100)
#define FAULT_FRONT_STEER_ENCODER_F ((uint16_t)0x0200)
#define FAULT_RC_SIGNAL_LOSS ((uint16_t)0x0400)
#define FAULT_HIGH_BYTE_RESERVED1 ((uint16_t)0x0800)
#define FAULT_HIGH_BYTE_RESERVED2 ((uint16_t)0x1000)
#define FAULT_HIGH_BYTE_RESERVED3 ((uint16_t)0x2000)
#define FAULT_HIGH_BYTE_RESERVED4 ((uint16_t)0x4000)
#define FAULT_HIGH_BYTE_RESERVED5 ((uint16_t)0x8000)
#define FAULT_BAT_UNDER_VOL_F ((uint16_t)0x0001)
#define FAULT_BAT_OVER_VOL_F ((uint16_t)0x0002)
#define FAULT_MOTOR1_COMM_F ((uint16_t)0x0004)
#define FAULT_MOTOR2_COMM_F ((uint16_t)0x0008)
#define FAULT_MOTOR3_COMM_F ((uint16_t)0x0010)
#define FAULT_MOTOR4_COMM_F ((uint16_t)0x0020)
#define FAULT_MOTOR_DRV_OVERHEAT_F ((uint16_t)0x0040)
#define FAULT_MOTOR_OVERCURRENT_F ((uint16_t)0x0080)
/*-------------------- Control/Feedback Messages -----------------------*/
/* No padding in the struct */
// reference: https://stackoverflow.com/questions/3318410/pragma-pack-effect
#pragma pack(push, 1)
// Note: id could be different for UART and CAN protocol
// Motion Control
typedef struct {
union
{
struct
{
uint8_t control_mode;
uint8_t fault_clear_flag;
int8_t linear_velocity_cmd;
int8_t angular_velocity_cmd;
uint8_t reserved0;
uint8_t reserved1;
uint8_t count;
uint8_t checksum;
} cmd;
uint8_t raw[8];
} data;
} MotionCmdMessage;
typedef struct {
union
{
struct
{
struct
{
uint8_t high_byte;
uint8_t low_byte;
} linear_velocity;
struct
{
uint8_t high_byte;
uint8_t low_byte;
} angular_velocity;
uint8_t reserved0;
uint8_t reserved1;
uint8_t count;
uint8_t checksum;
} status;
uint8_t raw[8];
} data;
} MotionStatusMessage;
// System Status Feedback
typedef struct {
union
{
struct
{
uint8_t base_state;
uint8_t control_mode;
struct
{
uint8_t high_byte;
uint8_t low_byte;
} battery_voltage;
struct
{
uint8_t high_byte;
uint8_t low_byte;
} fault_code;
uint8_t count;
uint8_t checksum;
} status;
uint8_t raw[8];
} data;
} SystemStatusMessage;
// System Configuration
typedef struct {
union
{
struct
{
uint8_t set_zero_steering;
uint8_t reserved0;
uint8_t reserved1;
uint8_t reserved2;
uint8_t reserved3;
uint8_t reserved4;
uint8_t count;
uint8_t checksum;
} status;
uint8_t raw[8];
} data;
} ConfigCmdMessage;
// System Configuration Status Feedback
typedef struct {
union
{
struct
{
uint8_t set_zero_steering;
uint8_t reserved0;
uint8_t reserved1;
uint8_t reserved2;
uint8_t reserved3;
uint8_t reserved4;
uint8_t count;
uint8_t checksum;
} status;
uint8_t raw[8];
} data;
} ConfigStatusMessage;
// Motor Driver Feedback
typedef struct
{
uint8_t motor_id;
union {
struct
{
struct
{
uint8_t high_byte;
uint8_t low_byte;
} current;
struct
{
uint8_t high_byte;
uint8_t low_byte;
} rpm;
int8_t temperature;
uint8_t reserved0;
uint8_t count;
uint8_t checksum;
} status;
uint8_t raw[8];
} data;
} MotorDriverStatusMessage;
// For convenience to access status/control message
typedef enum
{
HunterMsgNone = 0x00,
// status messages
HunterMotionStatusMsg = 0x01,
HunterSystemStatusMsg = 0x03,
HunterMotorDriverStatusMsg = 0x04,
HunterConfigStatusMsg = 0x05,
// control messages
HunterMotionCmdMsg = 0x21,
HunterConfigCmdMsg = 0x22
} HunterMsgType;
typedef struct
{
HunterMsgType type;
union {
// status messages
MotionStatusMessage motion_status_msg;
SystemStatusMessage system_status_msg;
ConfigStatusMessage config_status_msg;
MotorDriverStatusMessage motor_driver_status_msg;
// control messages
MotionCmdMessage motion_cmd_msg;
ConfigCmdMessage config_cmd_msg;
} body;
} HunterMessage;
#pragma pack(pop)
#ifdef __cplusplus
}
#endif
#endif /* HUNTER_PROTOCOL_H */

View File

@@ -1,75 +0,0 @@
/*
* hunter_types.hpp
*
* Created on: Apr 01, 2020 09:43
* Description:
*
* Copyright (c) 2019 Ruixiang Du (rdu)
*/
#ifndef HUNTER_TYPES_HPP
#define HUNTER_TYPES_HPP
#include <cstdint>
#include <iostream>
namespace westonrobot
{
struct HunterState
{
struct MotorState
{
double current = 0; // in A
double rpm = 0;
double temperature = 0;
};
// base state
uint8_t base_state = 0;
uint8_t control_mode = 0;
uint16_t fault_code = 0;
double battery_voltage = 0.0;
uint8_t set_zero_steering = 0;
// motor state
static constexpr uint8_t motor_num = 3;
MotorState motor_states[motor_num];
// motion state
double linear_velocity = 0;
double steering_angle = 0;
};
struct HunterMotionCmd
{
enum class FaultClearFlag
{
NO_FAULT = 0x00,
BAT_UNDER_VOL = 0x01,
BAT_OVER_VOL = 0x02,
MOTOR1_COMM = 0x03,
MOTOR2_COMM = 0x04,
MOTOR3_COMM = 0x05,
MOTOR4_COMM = 0x06,
MOTOR_DRV_OVERHEAT = 0x07,
MOTOR_OVERCURRENT = 0x08
};
HunterMotionCmd(int8_t linear = 0, int8_t angular = 0,
FaultClearFlag fault_clr_flag = FaultClearFlag::NO_FAULT)
: linear_velocity(linear), angular_velocity(angular),
fault_clear_flag(fault_clr_flag) {}
int8_t linear_velocity;
int8_t angular_velocity;
FaultClearFlag fault_clear_flag;
static constexpr double max_linear_velocity = 1.5; // 1.5 m/s
static constexpr double min_linear_velocity = -1.5; // -1.5 m/s
static constexpr double max_steering_angle = 0.4622; // 0.4622 rad ~= 26.5 degree
static constexpr double min_steering_angle = -0.4622; // -0.4622 rad
};
} // namespace westonrobot
#endif /* HUNTER_TYPES_HPP */

View File

@@ -1,78 +0,0 @@
/*
* scout_base.hpp
*
* Created on: Jun 04, 2019 01:22
* Description:
*
* Copyright (c) 2019 Ruixiang Du (rdu)
*/
#ifndef SCOUT_BASE_HPP
#define SCOUT_BASE_HPP
#include <string>
#include <cstdint>
#include <thread>
#include <mutex>
#include <functional>
#include "wrp_sdk/platforms/common/mobile_base.hpp"
#include "wrp_sdk/platforms/scout/scout_protocol.h"
#include "wrp_sdk/platforms/scout/scout_can_parser.h"
#include "wrp_sdk/platforms/scout/scout_uart_parser.h"
#include "wrp_sdk/platforms/scout/scout_types.hpp"
namespace westonrobot {
class ScoutBase : public MobileBase {
public:
ScoutBase() : MobileBase(){};
~ScoutBase() = default;
public:
// motion control
void SetMotionCommand(double linear_vel, double angular_vel,
ScoutMotionCmd::FaultClearFlag fault_clr_flag =
ScoutMotionCmd::FaultClearFlag::NO_FAULT);
// light control
void SetLightCommand(ScoutLightCmd cmd);
void DisableLightCmdControl();
// get robot state
ScoutState GetScoutState();
private:
// serial port buffer
uint8_t tx_cmd_len_;
uint8_t tx_buffer_[SCOUT_CMD_BUF_LEN];
// cmd/status update related variables
std::mutex scout_state_mutex_;
std::mutex motion_cmd_mutex_;
std::mutex light_cmd_mutex_;
ScoutState scout_state_;
ScoutMotionCmd current_motion_cmd_;
ScoutLightCmd current_light_cmd_;
bool light_ctrl_enabled_ = false;
bool light_ctrl_requested_ = false;
// internal functions
void SendRobotCmd() override;
void ParseCANFrame(can_frame *rx_frame);
void ParseUARTBuffer(uint8_t *buf, const size_t bufsize,
size_t bytes_received);
void SendMotionCmd(uint8_t count);
void SendLightCmd(uint8_t count);
void NewStatusMsgReceivedCallback(const ScoutMessage &msg);
public:
static void UpdateScoutState(const ScoutMessage &status_msg,
ScoutState &state);
};
} // namespace westonrobot
#endif /* SCOUT_BASE_HPP */

View File

@@ -1,42 +0,0 @@
/*
* scout_can_parser.h
*
* Created on: Aug 31, 2019 04:23
* Description:
*
* Copyright (c) 2019 Ruixiang Du (rdu)
*/
#ifndef SCOUT_CAN_PARSER_H
#define SCOUT_CAN_PARSER_H
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
#include "wrp_sdk/platforms/scout/scout_protocol.h"
#ifdef __linux__
#include <linux/can.h>
#else
struct can_frame
{
uint32_t can_id;
uint8_t can_dlc;
uint8_t data[8]__attribute__((aligned(8)));
};
#endif
bool DecodeScoutMsgFromCAN(const struct can_frame *rx_frame, ScoutMessage *msg);
void EncodeScoutMsgToCAN(const ScoutMessage *msg, struct can_frame *tx_frame);
uint8_t CalcScoutCANChecksum(uint16_t id, uint8_t *data, uint8_t dlc);
#ifdef __cplusplus
}
#endif
#endif /* SCOUT_CAN_PARSER_H */

View File

@@ -1,275 +0,0 @@
/*
* scout_protocol.h
*
* Created on: Aug 07, 2019 21:49
* Description:
*
* Copyright (c) 2019 Ruixiang Du (rdu)
*/
#ifndef SCOUT_PROTOCOL_H
#define SCOUT_PROTOCOL_H
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#define SCOUT_CMD_BUF_LEN 32
#define SCOUT_STATUS_BUF_LEN 32
#define SCOUT_FRAME_SIZE 13
#define SCOUT_MOTOR1_ID ((uint8_t)0x00)
#define SCOUT_MOTOR2_ID ((uint8_t)0x01)
#define SCOUT_MOTOR3_ID ((uint8_t)0x02)
#define SCOUT_MOTOR4_ID ((uint8_t)0x03)
// UART Definitions
#define UART_FRAME_SYSTEM_STATUS_ID ((uint8_t)0x01)
#define UART_FRAME_MOTION_STATUS_ID ((uint8_t)0x02)
#define UART_FRAME_MOTOR1_DRIVER_STATUS_ID ((uint8_t)0x03)
#define UART_FRAME_MOTOR2_DRIVER_STATUS_ID ((uint8_t)0x04)
#define UART_FRAME_MOTOR3_DRIVER_STATUS_ID ((uint8_t)0x05)
#define UART_FRAME_MOTOR4_DRIVER_STATUS_ID ((uint8_t)0x06)
#define UART_FRAME_LIGHT_STATUS_ID ((uint8_t)0x07)
#define UART_FRAME_MOTION_CONTROL_ID ((uint8_t)0x01)
#define UART_FRAME_LIGHT_CONTROL_ID ((uint8_t)0x02)
// CAN Definitions
#define CAN_MSG_MOTION_CONTROL_CMD_ID ((uint32_t)0x130)
#define CAN_MSG_MOTION_CONTROL_STATUS_ID ((uint32_t)0x131)
#define CAN_MSG_LIGHT_CONTROL_CMD_ID ((uint32_t)0x140)
#define CAN_MSG_LIGHT_CONTROL_STATUS_ID ((uint32_t)0x141)
#define CAN_MSG_SYSTEM_STATUS_STATUS_ID ((uint32_t)0x151)
#define CAN_MSG_MOTOR1_DRIVER_STATUS_ID ((uint32_t)0x200)
#define CAN_MSG_MOTOR2_DRIVER_STATUS_ID ((uint32_t)0x201)
#define CAN_MSG_MOTOR3_DRIVER_STATUS_ID ((uint32_t)0x202)
#define CAN_MSG_MOTOR4_DRIVER_STATUS_ID ((uint32_t)0x203)
/*--------------------- Control/State Constants ------------------------*/
// Motion Control
#define CTRL_MODE_REMOTE ((uint8_t)0x00)
#define CTRL_MODE_CMD_CAN ((uint8_t)0x01)
#define CTRL_MODE_CMD_UART ((uint8_t)0x02)
#define CTRL_MODE_COMMANDED ((uint8_t)0x03)
#define FAULT_CLR_NONE ((uint8_t)0x00)
#define FAULT_CLR_BAT_UNDER_VOL ((uint8_t)0x01)
#define FAULT_CLR_BAT_OVER_VOL ((uint8_t)0x02)
#define FAULT_CLR_MOTOR1_COMM ((uint8_t)0x03)
#define FAULT_CLR_MOTOR2_COMM ((uint8_t)0x04)
#define FAULT_CLR_MOTOR3_COMM ((uint8_t)0x05)
#define FAULT_CLR_MOTOR4_COMM ((uint8_t)0x06)
#define FAULT_CLR_MOTOR_DRV_OVERHEAT ((uint8_t)0x07)
#define FAULT_CLR_MOTOR_OVERCURRENT ((uint8_t)0x08)
// Light Control
#define LIGHT_DISABLE_CTRL ((uint8_t)0x00)
#define LIGHT_ENABLE_CTRL ((uint8_t)0x01)
#define LIGHT_MODE_CONST_OFF ((uint8_t)0x00)
#define LIGHT_MODE_CONST_ON ((uint8_t)0x01)
#define LIGHT_MODE_BREATH ((uint8_t)0x02)
#define LIGHT_MODE_CUSTOM ((uint8_t)0x03)
// System Status Feedback
#define BASE_STATE_NORMAL ((uint8_t)0x00)
#define BASE_STATE_ESTOP ((uint8_t)0x01)
#define BASE_STATE_EXCEPTION ((uint8_t)0x02)
#define FAULT_CAN_CHECKSUM_ERROR ((uint16_t)0x0100)
#define FAULT_MOTOR_DRV_OVERHEAT_W ((uint16_t)0x0200)
#define FAULT_MOTOR_OVERCURRENT_W ((uint16_t)0x0400)
#define FAULT_BAT_UNDER_VOL_W ((uint16_t)0x0800)
#define FAULT_RC_SIGNAL_LOSS ((uint16_t)0x1000)
#define FAULT_HIGH_BYTE_RESERVED2 ((uint16_t)0x2000)
#define FAULT_HIGH_BYTE_RESERVED3 ((uint16_t)0x4000)
#define FAULT_HIGH_BYTE_RESERVED4 ((uint16_t)0x8000)
#define FAULT_BAT_UNDER_VOL_F ((uint16_t)0x0001)
#define FAULT_BAT_OVER_VOL_F ((uint16_t)0x0002)
#define FAULT_MOTOR1_COMM_F ((uint16_t)0x0004)
#define FAULT_MOTOR2_COMM_F ((uint16_t)0x0008)
#define FAULT_MOTOR3_COMM_F ((uint16_t)0x0010)
#define FAULT_MOTOR4_COMM_F ((uint16_t)0x0020)
#define FAULT_MOTOR_DRV_OVERHEAT_F ((uint16_t)0x0040)
#define FAULT_MOTOR_OVERCURRENT_F ((uint16_t)0x0080)
/*-------------------- Control/Feedback Messages -----------------------*/
/* No padding in the struct */
// reference: https://stackoverflow.com/questions/3318410/pragma-pack-effect
#pragma pack(push, 1)
// Note: id could be different for UART and CAN protocol
// Motion Control
typedef struct {
union
{
struct
{
uint8_t control_mode;
uint8_t fault_clear_flag;
int8_t linear_velocity_cmd;
int8_t angular_velocity_cmd;
uint8_t reserved0;
uint8_t reserved1;
uint8_t count;
uint8_t checksum;
} cmd;
uint8_t raw[8];
} data;
} MotionControlMessage;
typedef struct {
union
{
struct
{
struct
{
uint8_t high_byte;
uint8_t low_byte;
} linear_velocity;
struct
{
uint8_t high_byte;
uint8_t low_byte;
} angular_velocity;
uint8_t reserved0;
uint8_t reserved1;
uint8_t count;
uint8_t checksum;
} status;
uint8_t raw[8];
} data;
} MotionStatusMessage;
// System Status Feedback
typedef struct {
union
{
struct
{
uint8_t base_state;
uint8_t control_mode;
struct
{
uint8_t high_byte;
uint8_t low_byte;
} battery_voltage;
struct
{
uint8_t high_byte;
uint8_t low_byte;
} fault_code;
uint8_t count;
uint8_t checksum;
} status;
uint8_t raw[8];
} data;
} SystemStatusMessage;
// Light Control
typedef struct {
union
{
struct
{
uint8_t light_ctrl_enable;
uint8_t front_light_mode;
uint8_t front_light_custom;
uint8_t rear_light_mode;
uint8_t rear_light_custom;
uint8_t reserved0;
uint8_t count;
uint8_t checksum;
} cmd;
uint8_t raw[8];
} data;
} LightControlMessage;
typedef struct {
union
{
struct
{
uint8_t light_ctrl_enable;
uint8_t front_light_mode;
uint8_t front_light_custom;
uint8_t rear_light_mode;
uint8_t rear_light_custom;
uint8_t reserved0;
uint8_t count;
uint8_t checksum;
} status;
uint8_t raw[8];
} data;
} LightStatusMessage;
// Motor Driver Feedback
typedef struct
{
uint8_t motor_id;
union {
struct
{
struct
{
uint8_t high_byte;
uint8_t low_byte;
} current;
struct
{
uint8_t high_byte;
uint8_t low_byte;
} rpm;
int8_t temperature;
uint8_t reserved0;
uint8_t count;
uint8_t checksum;
} status;
uint8_t raw[8];
} data;
} MotorDriverStatusMessage;
// For convenience to access status/control message
typedef enum
{
ScoutMsgNone = 0x00,
// status messages
ScoutMotionStatusMsg = 0x01,
ScoutLightStatusMsg = 0x02,
ScoutSystemStatusMsg = 0x03,
ScoutMotorDriverStatusMsg = 0x04,
// control messages
ScoutMotionControlMsg = 0x21,
ScoutLightControlMsg = 0x22
} ScoutMsgType;
typedef struct
{
ScoutMsgType type;
union {
// status messages
MotionStatusMessage motion_status_msg;
LightStatusMessage light_status_msg;
SystemStatusMessage system_status_msg;
MotorDriverStatusMessage motor_driver_status_msg;
// control messages
MotionControlMessage motion_control_msg;
LightControlMessage light_control_msg;
} body;
} ScoutMessage;
#pragma pack(pop)
#ifdef __cplusplus
}
#endif
#endif /* SCOUT_PROTOCOL_H */

View File

@@ -1,112 +0,0 @@
/*
* scout_state.hpp
*
* Created on: Jun 11, 2019 08:48
* Description:
*
* Copyright (c) 2019 Ruixiang Du (rdu)
*/
#ifndef SCOUT_STATE_HPP
#define SCOUT_STATE_HPP
#include <cstdint>
#include <iostream>
namespace westonrobot
{
struct ScoutState
{
enum MotorID
{
FRONT_RIGHT = 0,
FRONT_LEFT = 1,
REAR_LEFT = 2,
REAR_RIGHT = 3
};
struct MotorState
{
double current = 0; // in A
double rpm = 0;
double temperature = 0;
};
struct LightState
{
uint8_t mode = 0;
uint8_t custom_value = 0;
};
// base state
uint8_t base_state = 0;
uint8_t control_mode = 0;
uint16_t fault_code = 0;
double battery_voltage = 0.0;
// motor state
static constexpr uint8_t motor_num = 4;
MotorState motor_states[motor_num];
// light state
bool light_control_enabled = false;
LightState front_light_state;
LightState rear_light_state;
// motion state
double linear_velocity = 0;
double angular_velocity = 0;
};
struct ScoutMotionCmd
{
enum class FaultClearFlag
{
NO_FAULT = 0x00,
BAT_UNDER_VOL = 0x01,
BAT_OVER_VOL = 0x02,
MOTOR1_COMM = 0x03,
MOTOR2_COMM = 0x04,
MOTOR3_COMM = 0x05,
MOTOR4_COMM = 0x06,
MOTOR_DRV_OVERHEAT = 0x07,
MOTOR_OVERCURRENT = 0x08
};
ScoutMotionCmd(int8_t linear = 0, int8_t angular = 0,
FaultClearFlag fault_clr_flag = FaultClearFlag::NO_FAULT)
: linear_velocity(linear), angular_velocity(angular),
fault_clear_flag(fault_clr_flag) {}
int8_t linear_velocity;
int8_t angular_velocity;
FaultClearFlag fault_clear_flag;
static constexpr double max_linear_velocity = 1.5; // 1.5 m/s
static constexpr double min_linear_velocity = -1.5; // -1.5 m/s
static constexpr double max_angular_velocity = 0.5235; // 0.5235 rad/s
static constexpr double min_angular_velocity = -0.5235; // -0.5235 rad/s
};
struct ScoutLightCmd
{
enum class LightMode
{
CONST_OFF = 0x00,
CONST_ON = 0x01,
BREATH = 0x02,
CUSTOM = 0x03
};
ScoutLightCmd() = default;
ScoutLightCmd(LightMode f_mode, uint8_t f_value, LightMode r_mode, uint8_t r_value) : front_mode(f_mode), front_custom_value(f_value),
rear_mode(r_mode), rear_custom_value(r_value) {}
LightMode front_mode;
uint8_t front_custom_value;
LightMode rear_mode;
uint8_t rear_custom_value;
};
} // namespace westonrobot
#endif /* SCOUT_STATE_HPP */

View File

@@ -1,32 +0,0 @@
/*
* scout_uart_parser.h
*
* Created on: Aug 14, 2019 12:01
* Description:
*
* Copyright (c) 2019 Ruixiang Du (rdu)
*/
#ifndef SCOUT_UART_PARSER_H
#define SCOUT_UART_PARSER_H
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <string.h>
#include <stdbool.h>
#include "wrp_sdk/platforms/scout/scout_protocol.h"
bool DecodeScoutMsgFromUART(uint8_t c, ScoutMessage *msg);
void EncodeScoutMsgToUART(const ScoutMessage *msg, uint8_t *buf, uint8_t *len);
uint8_t CalcScoutUARTChecksum(uint8_t *buf, uint8_t len);
#ifdef __cplusplus
}
#endif
#endif /* SCOUT_UART_PARSER_H */

View File

@@ -1,109 +0,0 @@
/*
* tracer_base.hpp
*
* Created on: Apr 14, 2020 10:21
* Description:
*
* Copyright (c) 2020 Ruixiang Du (rdu)
*/
#ifndef TRACER_BASE_HPP
#define TRACER_BASE_HPP
#include <string>
#include <cstdint>
#include <thread>
#include <mutex>
#include <functional>
#include "async_io/async_can.hpp"
#include "async_io/async_serial.hpp"
#include "tracer_protocol/tracer_protocol.h"
#include "tracer_protocol/tracer_can_parser.h"
#include "tracer_base/tracer_types.hpp"
namespace westonrobot
{
class TracerBase
{
public:
TracerBase() = default;
~TracerBase();
// do not allow copy
TracerBase(const TracerBase &tracer) = delete;
TracerBase &operator=(const TracerBase &tracer) = delete;
public:
// connect to roboot from CAN
void Connect(std::string dev_name);
// disconnect from roboot, only valid for serial port
void Disconnect();
// cmd thread runs at 100Hz (10ms) by default
void SetCmdThreadPeriodMs(int32_t period_ms) { cmd_thread_period_ms_ = period_ms; };
// motion control
void SetMotionCommand(double linear_vel, double angular_vel,
TracerMotionCmd::FaultClearFlag fault_clr_flag = TracerMotionCmd::FaultClearFlag::NO_FAULT);
// light control
void SetLightCommand(TracerLightCmd cmd);
void DisableLightCmdControl();
// get robot state
TracerState GetTracerState();
private:
// hardware communication interface
std::shared_ptr<AsyncCAN> can_if_;
std::shared_ptr<AsyncSerial> serial_if_;
// CAN priority higher than serial if both connected
bool can_connected_ = false;
bool serial_connected_ = false;
// serial port related variables
uint8_t tx_cmd_len_;
uint8_t tx_buffer_[TRACER_CMD_BUF_LEN];
// cmd/status update related variables
std::thread cmd_thread_;
std::mutex tracer_state_mutex_;
std::mutex motion_cmd_mutex_;
std::mutex light_cmd_mutex_;
TracerState tracer_state_;
TracerMotionCmd current_motion_cmd_;
TracerLightCmd current_light_cmd_;
int32_t cmd_thread_period_ms_ = 10;
bool cmd_thread_started_ = false;
bool light_ctrl_enabled_ = false;
bool light_ctrl_requested_ = false;
// internal functions
void ConfigureCANBus(const std::string &can_if_name = "can1");
void ConfigureSerial(const std::string uart_name = "/dev/ttyUSB0", int32_t baud_rate = 115200);
void StartCmdThread();
void ControlLoop(int32_t period_ms);
void SendMotionCmd(uint8_t count);
void SendLightCmd(uint8_t count);
void ParseCANFrame(can_frame *rx_frame);
void ParseUARTBuffer(uint8_t *buf, const size_t bufsize, size_t bytes_received);
void NewStatusMsgReceivedCallback(const TracerMessage &msg);
public:
static void UpdateTracerState(const TracerMessage &status_msg, TracerState &state);
};
} // namespace westonrobot
#endif /* TRACER_BASE_HPP */

View File

@@ -1,42 +0,0 @@
/*
* tracer_can_parser.h
*
* Created on: Apr 14, 2020 10:52
* Description:
*
* Copyright (c) 2020 Ruixiang Du (rdu)
*/
#ifndef TRACER_CAN_PARSER_H
#define TRACER_CAN_PARSER_H
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
#include "tracer_protocol/tracer_protocol.h"
#ifdef __linux__
#include <linux/can.h>
#else
struct can_frame
{
uint32_t can_id;
uint8_t can_dlc;
uint8_t data[8]__attribute__((aligned(8)));
};
#endif
bool DecodeTracerMsgFromCAN(const struct can_frame *rx_frame, TracerMessage *msg);
void EncodeTracerMsgToCAN(const TracerMessage *msg, struct can_frame *tx_frame);
uint8_t CalcTracerCANChecksum(uint16_t id, uint8_t *data, uint8_t dlc);
#ifdef __cplusplus
}
#endif
#endif /* TRACER_CAN_PARSER_H */

View File

@@ -1,259 +0,0 @@
/*
* tracer_protocol.h
*
* Created on: Apr 14, 2020 10:34
* Description:
*
* Copyright (c) 2020 Ruixiang Du (rdu)
*/
#ifndef TRACER_PROTOCOL_H
#define TRACER_PROTOCOL_H
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#define TRACER_CMD_BUF_LEN 32
#define TRACER_STATUS_BUF_LEN 32
#define TRACER_FRAME_SIZE 13
#define TRACER_MOTOR1_ID ((uint8_t)0x00)
#define TRACER_MOTOR2_ID ((uint8_t)0x01)
// CAN Definitions
#define CAN_MSG_MOTION_CMD_ID ((uint32_t)0x130)
#define CAN_MSG_MOTION_STATUS_ID ((uint32_t)0x131)
#define CAN_MSG_LIGHT_CONTROL_CMD_ID ((uint32_t)0x140)
#define CAN_MSG_LIGHT_CONTROL_STATUS_ID ((uint32_t)0x141)
#define CAN_MSG_SYSTEM_STATUS_STATUS_ID ((uint32_t)0x151)
#define CAN_MSG_MOTOR1_DRIVER_STATUS_ID ((uint32_t)0x201)
#define CAN_MSG_MOTOR2_DRIVER_STATUS_ID ((uint32_t)0x202)
/*--------------------- Control/State Constants ------------------------*/
// Motion Control
#define CTRL_MODE_REMOTE ((uint8_t)0x00)
#define CTRL_MODE_CMD_CAN ((uint8_t)0x01)
#define CTRL_MODE_CMD_UART ((uint8_t)0x02)
#define CTRL_MODE_COMMANDED ((uint8_t)0x03)
#define FAULT_CLR_NONE ((uint8_t)0x00)
#define FAULT_CLR_BAT_UNDER_VOL ((uint8_t)0x01)
#define FAULT_CLR_BAT_OVER_VOL ((uint8_t)0x02)
#define FAULT_CLR_MOTOR1_COMM ((uint8_t)0x03)
#define FAULT_CLR_MOTOR2_COMM ((uint8_t)0x04)
#define FAULT_CLR_MOTOR3_COMM ((uint8_t)0x05)
#define FAULT_CLR_MOTOR4_COMM ((uint8_t)0x06)
#define FAULT_CLR_MOTOR_DRV_OVERHEAT ((uint8_t)0x07)
#define FAULT_CLR_MOTOR_OVERCURRENT ((uint8_t)0x08)
// Light Control
#define LIGHT_DISABLE_CTRL ((uint8_t)0x00)
#define LIGHT_ENABLE_CTRL ((uint8_t)0x01)
#define LIGHT_MODE_CONST_OFF ((uint8_t)0x00)
#define LIGHT_MODE_CONST_ON ((uint8_t)0x01)
#define LIGHT_MODE_BREATH ((uint8_t)0x02)
#define LIGHT_MODE_CUSTOM ((uint8_t)0x03)
// System Status Feedback
#define BASE_STATE_NORMAL ((uint8_t)0x00)
#define BASE_STATE_ESTOP ((uint8_t)0x01)
#define BASE_STATE_EXCEPTION ((uint8_t)0x02)
#define FAULT_CAN_CHECKSUM_ERROR ((uint16_t)0x0100)
#define FAULT_FRONT_STEER_ENCODER_F ((uint16_t)0x0200)
#define FAULT_RC_SIGNAL_LOSS ((uint16_t)0x0400)
#define FAULT_HIGH_BYTE_RESERVED1 ((uint16_t)0x0800)
#define FAULT_HIGH_BYTE_RESERVED2 ((uint16_t)0x1000)
#define FAULT_HIGH_BYTE_RESERVED3 ((uint16_t)0x2000)
#define FAULT_HIGH_BYTE_RESERVED4 ((uint16_t)0x4000)
#define FAULT_HIGH_BYTE_RESERVED5 ((uint16_t)0x8000)
#define FAULT_BAT_UNDER_VOL_F ((uint16_t)0x0001)
#define FAULT_BAT_OVER_VOL_F ((uint16_t)0x0002)
#define FAULT_MOTOR1_COMM_F ((uint16_t)0x0004)
#define FAULT_MOTOR2_COMM_F ((uint16_t)0x0008)
#define FAULT_RESERVED1 ((uint16_t)0x0010)
#define FAULT_RESERVED2 ((uint16_t)0x0020)
#define FAULT_MOTOR_DRV_OVERHEAT_F ((uint16_t)0x0040)
#define FAULT_MOTOR_OVERCURRENT_F ((uint16_t)0x0080)
/*-------------------- Control/Feedback Messages -----------------------*/
/* No padding in the struct */
// reference: https://stackoverflow.com/questions/3318410/pragma-pack-effect
#pragma pack(push, 1)
// Note: id could be different for UART and CAN protocol
// Motion Control
typedef struct {
union
{
struct
{
uint8_t control_mode;
uint8_t fault_clear_flag;
int8_t linear_velocity_cmd;
int8_t angular_velocity_cmd;
uint8_t reserved0;
uint8_t reserved1;
uint8_t count;
uint8_t checksum;
} cmd;
uint8_t raw[8];
} data;
} MotionCmdMessage;
typedef struct {
union
{
struct
{
struct
{
uint8_t high_byte;
uint8_t low_byte;
} linear_velocity;
struct
{
uint8_t high_byte;
uint8_t low_byte;
} angular_velocity;
uint8_t reserved0;
uint8_t reserved1;
uint8_t count;
uint8_t checksum;
} status;
uint8_t raw[8];
} data;
} MotionStatusMessage;
// System Status Feedback
typedef struct {
union
{
struct
{
uint8_t base_state;
uint8_t control_mode;
struct
{
uint8_t high_byte;
uint8_t low_byte;
} battery_voltage;
struct
{
uint8_t high_byte;
uint8_t low_byte;
} fault_code;
uint8_t count;
uint8_t checksum;
} status;
uint8_t raw[8];
} data;
} SystemStatusMessage;
// Light Control
typedef struct {
union
{
struct
{
uint8_t light_ctrl_enable;
uint8_t front_light_mode;
uint8_t front_light_custom;
uint8_t rear_light_mode;
uint8_t rear_light_custom;
uint8_t reserved0;
uint8_t count;
uint8_t checksum;
} cmd;
uint8_t raw[8];
} data;
} LightControlMessage;
typedef struct {
union
{
struct
{
uint8_t light_ctrl_enable;
uint8_t front_light_mode;
uint8_t front_light_custom;
uint8_t rear_light_mode;
uint8_t rear_light_custom;
uint8_t reserved0;
uint8_t count;
uint8_t checksum;
} status;
uint8_t raw[8];
} data;
} LightStatusMessage;
// Motor Driver Feedback
typedef struct
{
uint8_t motor_id;
union {
struct
{
struct
{
uint8_t high_byte;
uint8_t low_byte;
} current;
struct
{
uint8_t high_byte;
uint8_t low_byte;
} rpm;
int8_t temperature;
uint8_t reserved0;
uint8_t count;
uint8_t checksum;
} status;
uint8_t raw[8];
} data;
} MotorDriverStatusMessage;
// For convenience to access status/control message
typedef enum
{
TracerMsgNone = 0x00,
// status messages
TracerMotionStatusMsg = 0x01,
TracerLightStatusMsg = 0x02,
TracerSystemStatusMsg = 0x03,
TracerMotorDriverStatusMsg = 0x04,
// control messages
TracerMotionCmdMsg = 0x21,
TracerLightControlMsg = 0x22
} TracerMsgType;
typedef struct
{
TracerMsgType type;
union {
// status messages
MotionStatusMessage motion_status_msg;
LightStatusMessage light_status_msg;
SystemStatusMessage system_status_msg;
MotorDriverStatusMessage motor_driver_status_msg;
// control messages
MotionCmdMessage motion_cmd_msg;
LightControlMessage light_control_msg;
} body;
} TracerMessage;
#pragma pack(pop)
#ifdef __cplusplus
}
#endif
#endif /* TRACER_PROTOCOL_H */

View File

@@ -1,111 +0,0 @@
/*
* tracer_types.hpp
*
* Created on: Apr 14, 2020 10:22
* Description:
*
* Copyright (c) 2020 Ruixiang Du (rdu)
*/
#ifndef TRACER_TYPES_HPP
#define TRACER_TYPES_HPP
#include <cstdint>
#include <iostream>
namespace westonrobot
{
struct TracerState
{
enum MotorID
{
FRONT_RIGHT = 0,
FRONT_LEFT = 1,
REAR_LEFT = 2,
REAR_RIGHT = 3
};
struct MotorState
{
double current = 0; // in A
double rpm = 0;
double temperature = 0;
};
struct LightState
{
uint8_t mode = 0;
uint8_t custom_value = 0;
};
// base state
uint8_t base_state = 0;
uint8_t control_mode = 0;
uint16_t fault_code = 0;
double battery_voltage = 0.0;
// motor state
MotorState motor_states[4];
// light state
bool light_control_enabled = false;
LightState front_light_state;
LightState rear_light_state;
// motion state
double linear_velocity = 0;
double angular_velocity = 0;
};
struct TracerMotionCmd
{
enum class FaultClearFlag
{
NO_FAULT = 0x00,
BAT_UNDER_VOL = 0x01,
BAT_OVER_VOL = 0x02,
MOTOR1_COMM = 0x03,
MOTOR2_COMM = 0x04,
MOTOR3_COMM = 0x05,
MOTOR4_COMM = 0x06,
MOTOR_DRV_OVERHEAT = 0x07,
MOTOR_OVERCURRENT = 0x08
};
TracerMotionCmd(int8_t linear = 0, int8_t angular = 0,
FaultClearFlag fault_clr_flag = FaultClearFlag::NO_FAULT)
: linear_velocity(linear), angular_velocity(angular),
fault_clear_flag(fault_clr_flag) {}
int8_t linear_velocity;
int8_t angular_velocity;
FaultClearFlag fault_clear_flag;
static constexpr double max_linear_velocity = 1.5; // 1.5 m/s
static constexpr double min_linear_velocity = -1.5; // -1.5 m/s
static constexpr double max_angular_velocity = 0.5235; // 0.5235 rad/s
static constexpr double min_angular_velocity = -0.5235; // -0.5235 rad/s
};
struct TracerLightCmd
{
enum class LightMode
{
CONST_OFF = 0x00,
CONST_ON = 0x01,
BREATH = 0x02,
CUSTOM = 0x03
};
TracerLightCmd() = default;
TracerLightCmd(LightMode f_mode, uint8_t f_value, LightMode r_mode, uint8_t r_value) : front_mode(f_mode), front_custom_value(f_value),
rear_mode(r_mode), rear_custom_value(r_value) {}
LightMode front_mode;
uint8_t front_custom_value;
LightMode rear_mode;
uint8_t rear_custom_value;
};
} // namespace westonrobot
#endif /* TRACER_TYPES_HPP */