mirror of
https://github.com/westonrobot/ugv_sdk
synced 2023-04-08 06:32:14 +08:00
made scout_base to be class template
This commit is contained in:
@@ -119,11 +119,8 @@ class AgilexBase : public RobotInterface {
|
||||
}
|
||||
|
||||
protected:
|
||||
std::mutex state_mutex_;
|
||||
// std::mutex motion_cmd_mutex_;
|
||||
MotionCommandMessage current_motion_cmd_;
|
||||
|
||||
ParserType parser_;
|
||||
std::mutex state_mutex_;
|
||||
|
||||
// communication interface
|
||||
bool can_connected_ = false;
|
||||
120
include/ugv_sdk/details/robot_base/scout_base.hpp
Normal file
120
include/ugv_sdk/details/robot_base/scout_base.hpp
Normal file
@@ -0,0 +1,120 @@
|
||||
/*
|
||||
* scout_base.hpp
|
||||
*
|
||||
* Created on: Dec 23, 2020 14:39
|
||||
* Description:
|
||||
*
|
||||
* Copyright (c) 2020 Ruixiang Du (rdu)
|
||||
*/
|
||||
|
||||
#ifndef SCOUT_BASE_HPP
|
||||
#define SCOUT_BASE_HPP
|
||||
|
||||
#include <string>
|
||||
#include <cstdint>
|
||||
#include <thread>
|
||||
#include <mutex>
|
||||
|
||||
#include "ugv_sdk/interface/scout_interface.hpp"
|
||||
#include "ugv_sdk/details/robot_base/agilex_base.hpp"
|
||||
#include "ugv_sdk/protocol_v2/protocol_v2_parser.hpp"
|
||||
|
||||
namespace westonrobot {
|
||||
template <typename Parser>
|
||||
class ScoutBase : public AgilexBase<Parser>, public ScoutInterface {
|
||||
public:
|
||||
ScoutBase() : AgilexBase<Parser>(){};
|
||||
~ScoutBase() = default;
|
||||
|
||||
// set up connection
|
||||
void Connect(std::string can_name) override {
|
||||
AgilexBase<Parser>::ConnectPort(
|
||||
can_name, std::bind(&ScoutBase<Parser>::ParseCANFrame, this,
|
||||
std::placeholders::_1));
|
||||
}
|
||||
|
||||
void Connect(std::string uart_name, uint32_t baudrate) override {
|
||||
// TODO
|
||||
}
|
||||
|
||||
// robot control
|
||||
void SetMotionCommand(double linear_vel, double angular_vel) override {
|
||||
AgilexBase<Parser>::SendMotionCommand(linear_vel, angular_vel, 0.0, 0.0);
|
||||
}
|
||||
|
||||
void SetLightCommand(LightMode f_mode, uint8_t f_value, LightMode r_mode,
|
||||
uint8_t r_value) override {
|
||||
AgilexBase<Parser>::SendLightCommand(f_mode, f_value, r_mode, r_value);
|
||||
}
|
||||
|
||||
// get robot state
|
||||
ScoutState GetRobotState() override {
|
||||
std::lock_guard<std::mutex> guard(AgilexBase<Parser>::state_mutex_);
|
||||
return scout_state_;
|
||||
}
|
||||
|
||||
void ResetRobotState() override {
|
||||
// TODO
|
||||
}
|
||||
|
||||
private:
|
||||
ScoutState scout_state_;
|
||||
|
||||
void ParseCANFrame(can_frame *rx_frame) override {
|
||||
AgxMessage status_msg;
|
||||
DecodeCanFrame(rx_frame, &status_msg);
|
||||
std::lock_guard<std::mutex> guard(AgilexBase<Parser>::state_mutex_);
|
||||
UpdateScoutState(status_msg, scout_state_);
|
||||
}
|
||||
|
||||
void UpdateScoutState(const AgxMessage &status_msg, ScoutState &state) {
|
||||
switch (status_msg.type) {
|
||||
case AgxMsgSystemState: {
|
||||
// std::cout << "system status feedback received" << std::endl;
|
||||
state.system_state = status_msg.body.system_state_msg;
|
||||
break;
|
||||
}
|
||||
case AgxMsgMotionState: {
|
||||
// std::cout << "motion control feedback received" << std::endl;
|
||||
state.motion_state = status_msg.body.motion_state_msg;
|
||||
break;
|
||||
}
|
||||
case AgxMsgLightState: {
|
||||
// std::cout << "light control feedback received" << std::endl;
|
||||
state.light_state = status_msg.body.light_state_msg;
|
||||
break;
|
||||
}
|
||||
case AgxMsgRcState: {
|
||||
state.rc_state = status_msg.body.rc_state_msg;
|
||||
break;
|
||||
}
|
||||
case AgxMsgActuatorHSState: {
|
||||
// std::cout << "actuator hs feedback received" << std::endl;
|
||||
state
|
||||
.actuator_hs_state[status_msg.body.actuator_hs_state_msg.motor_id] =
|
||||
status_msg.body.actuator_hs_state_msg;
|
||||
break;
|
||||
}
|
||||
case AgxMsgActuatorLSState: {
|
||||
// std::cout << "actuator ls feedback received" << std::endl;
|
||||
state
|
||||
.actuator_ls_state[status_msg.body.actuator_ls_state_msg.motor_id] =
|
||||
status_msg.body.actuator_ls_state_msg;
|
||||
break;
|
||||
}
|
||||
/* sensor feedback */
|
||||
case AgxMsgOdometry: {
|
||||
// std::cout << "Odometer msg feedback received" << std::endl;
|
||||
state.odometry = status_msg.body.odometry_msg;
|
||||
}
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
using ScoutBaseV2 = ScoutBase<ProtocolV2Parser>;
|
||||
} // namespace westonrobot
|
||||
|
||||
#endif /* SCOUT_BASE_HPP */
|
||||
@@ -19,10 +19,10 @@
|
||||
#include "ugv_sdk/protocol_v2/agilex_base.hpp"
|
||||
|
||||
namespace westonrobot {
|
||||
class TracerBase : public AgilexBase, public TracerInterface {
|
||||
class TracerBaseV2 : public AgilexBase, public TracerInterface {
|
||||
public:
|
||||
TracerBase() : AgilexBase(){};
|
||||
~TracerBase() = default;
|
||||
TracerBaseV2() : AgilexBase(){};
|
||||
~TracerBaseV2() = default;
|
||||
|
||||
// set up connection
|
||||
void Connect(std::string can_name) override;
|
||||
@@ -31,19 +31,21 @@ struct ParserInterface {
|
||||
virtual bool DecodeMessage(const struct can_frame *rx_frame,
|
||||
AgxMessage *msg) = 0;
|
||||
virtual void EncodeMessage(const AgxMessage *msg,
|
||||
struct can_frame *tx_frame) = 0;
|
||||
struct can_frame *tx_frame) = 0;
|
||||
virtual uint8_t CalculateChecksum(uint16_t id, uint8_t *data,
|
||||
uint8_t dlc) = 0;
|
||||
|
||||
// UART support
|
||||
virtual bool DecodeMessage(uint8_t *data, uint8_t dlc, AgxMessage *msg){
|
||||
// throw exception
|
||||
virtual bool DecodeMessage(uint8_t *data, uint8_t dlc, AgxMessage *msg) {
|
||||
// throw exception
|
||||
return false;
|
||||
};
|
||||
virtual void EncodeMessage(const AgxMessage *msg, uint8_t *buf, uint8_t *len){
|
||||
// throw exception
|
||||
};
|
||||
virtual uint8_t CalculateChecksum(uint8_t *buf, uint8_t len){
|
||||
// throw exception
|
||||
virtual uint8_t CalculateChecksum(uint8_t *buf, uint8_t len) {
|
||||
// throw exception
|
||||
return 0;
|
||||
};
|
||||
};
|
||||
|
||||
|
||||
@@ -24,7 +24,7 @@ class ScoutRobot : public RobotInterface, public ScoutInterface {
|
||||
void Connect(std::string can_name) override;
|
||||
void Connect(std::string uart_name, uint32_t baudrate) override;
|
||||
|
||||
void EnableCommandedMode();
|
||||
void EnableCommandedMode() override;
|
||||
|
||||
void SetMotionCommand(double linear_vel, double angular_vel) override;
|
||||
void SetLightCommand(LightMode f_mode, uint8_t f_value, LightMode r_mode,
|
||||
|
||||
@@ -1,14 +1,14 @@
|
||||
/*
|
||||
* scout_base.hpp
|
||||
* scout_base_v1.hpp
|
||||
*
|
||||
* Created on: Dec 23, 2020 14:39
|
||||
* Created on: Jul 08, 2021 22:47
|
||||
* Description:
|
||||
*
|
||||
* Copyright (c) 2020 Ruixiang Du (rdu)
|
||||
* Copyright (c) 2021 Ruixiang Du (rdu)
|
||||
*/
|
||||
|
||||
#ifndef SCOUT_BASE_HPP
|
||||
#define SCOUT_BASE_HPP
|
||||
#ifndef SCOUT_BASE_V1_HPP
|
||||
#define SCOUT_BASE_V1_HPP
|
||||
|
||||
#include <string>
|
||||
#include <cstdint>
|
||||
@@ -18,13 +18,14 @@
|
||||
#include "ugv_sdk/interface/scout_interface.hpp"
|
||||
|
||||
#include "ugv_sdk/mobile_base/agilex_base.hpp"
|
||||
#include "ugv_sdk/protocol_v2/protocol_v2_parser.hpp"
|
||||
#include "ugv_sdk/protocol_v1/scout_protocol_v1_parser.hpp"
|
||||
|
||||
namespace westonrobot {
|
||||
class ScoutBaseV2 : public AgilexBase<ProtocolV2Parser>, public ScoutInterface {
|
||||
class ScoutBaseV1 : public AgilexBase<ScoutProtocolV1Parser>,
|
||||
public ScoutInterface {
|
||||
public:
|
||||
ScoutBaseV2() : AgilexBase(){};
|
||||
~ScoutBaseV2() = default;
|
||||
ScoutBaseV1() : AgilexBase<ScoutProtocolV1Parser>(){};
|
||||
~ScoutBaseV1() = default;
|
||||
|
||||
// set up connection
|
||||
void Connect(std::string can_name) override;
|
||||
@@ -48,4 +49,4 @@ class ScoutBaseV2 : public AgilexBase<ProtocolV2Parser>, public ScoutInterface {
|
||||
};
|
||||
} // namespace westonrobot
|
||||
|
||||
#endif /* SCOUT_BASE_HPP */
|
||||
#endif /* SCOUT_BASE_V1_HPP */
|
||||
@@ -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 "ugv_sdk/protocol_v1/scout_protocol_v1.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 */
|
||||
@@ -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 */
|
||||
32
include/ugv_sdk/protocol_v1/scout_protocol_v1_parser.hpp
Normal file
32
include/ugv_sdk/protocol_v1/scout_protocol_v1_parser.hpp
Normal file
@@ -0,0 +1,32 @@
|
||||
/*
|
||||
* scout_protocol_v1_parser.hpp
|
||||
*
|
||||
* Created on: Jul 08, 2021 22:30
|
||||
* Description:
|
||||
*
|
||||
* Copyright (c) 2021 Ruixiang Du (rdu)
|
||||
*/
|
||||
|
||||
#ifndef SCOUT_PROTOCOL_V1_PARSER_HPP
|
||||
#define SCOUT_PROTOCOL_V1_PARSER_HPP
|
||||
|
||||
#include "ugv_sdk/interface/parser_interface.hpp"
|
||||
|
||||
namespace westonrobot {
|
||||
class ScoutProtocolV1Parser : public ParserInterface {
|
||||
public:
|
||||
bool DecodeMessage(const struct can_frame *rx_frame,
|
||||
AgxMessage *msg) override;
|
||||
void EncodeMessage(const AgxMessage *msg,
|
||||
struct can_frame *tx_frame) override;
|
||||
uint8_t CalculateChecksum(uint16_t id, uint8_t *data, uint8_t dlc) override;
|
||||
|
||||
// UART support
|
||||
bool DecodeMessage(uint8_t *data, uint8_t dlc, AgxMessage *msg) override;
|
||||
void EncodeMessage(const AgxMessage *msg, uint8_t *buf,
|
||||
uint8_t *len) override;
|
||||
uint8_t CalculateChecksum(uint8_t *buf, uint8_t len) override;
|
||||
};
|
||||
} // namespace westonrobot
|
||||
|
||||
#endif /* SCOUT_PROTOCOL_V1_PARSER_HPP */
|
||||
Reference in New Issue
Block a user