updated scout base to use class MobileBase

This commit is contained in:
Ruixiang Du
2020-07-28 18:30:26 +08:00
parent 981a64b1af
commit 7fcd239c69
3 changed files with 289 additions and 378 deletions

View File

@@ -36,10 +36,6 @@ class HunterBase : public MobileBase {
HunterMotionCmd::FaultClearFlag::NO_FAULT);
private:
// serial port related variables
uint8_t tx_cmd_len_;
uint8_t tx_buffer_[HUNTER_CMD_BUF_LEN];
// cmd/status update related variables
std::mutex hunter_state_mutex_;
std::mutex motion_cmd_mutex_;

View File

@@ -1,9 +1,9 @@
/*
/*
* scout_base.hpp
*
*
* Created on: Jun 04, 2019 01:22
* Description:
*
* Description:
*
* Copyright (c) 2019 Ruixiang Du (rdu)
*/
@@ -16,95 +16,67 @@
#include <mutex>
#include <functional>
#include "wrp_sdk/asyncio/async_can.hpp"
#include "wrp_sdk/asyncio/async_serial.hpp"
#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:
ScoutBase() = default;
~ScoutBase();
namespace westonrobot {
class ScoutBase : public MobileBase {
public:
ScoutBase() : MobileBase(){};
~ScoutBase() = default;
// do not allow copy
ScoutBase(const ScoutBase &scout) = delete;
ScoutBase &operator=(const ScoutBase &scout) = delete;
public:
// motion control
void SetMotionCommand(double linear_vel, double angular_vel,
ScoutMotionCmd::FaultClearFlag fault_clr_flag =
ScoutMotionCmd::FaultClearFlag::NO_FAULT);
public:
// connect to roboot from CAN or serial
void Connect(std::string dev_name, int32_t baud_rate = 0);
// light control
void SetLightCommand(ScoutLightCmd cmd);
void DisableLightCmdControl();
// disconnect from roboot, only valid for serial port
void Disconnect();
// get robot state
ScoutState GetScoutState();
// cmd thread runs at 100Hz (10ms) by default
void SetCmdThreadPeriodMs(int32_t period_ms) { cmd_thread_period_ms_ = period_ms; };
private:
// serial port buffer
uint8_t tx_cmd_len_;
uint8_t tx_buffer_[SCOUT_CMD_BUF_LEN];
// motion control
void SetMotionCommand(double linear_vel, double angular_vel,
ScoutMotionCmd::FaultClearFlag fault_clr_flag = ScoutMotionCmd::FaultClearFlag::NO_FAULT);
// cmd/status update related variables
std::thread cmd_thread_;
std::mutex scout_state_mutex_;
std::mutex motion_cmd_mutex_;
std::mutex light_cmd_mutex_;
// light control
void SetLightCommand(ScoutLightCmd cmd);
void DisableLightCmdControl();
ScoutState scout_state_;
ScoutMotionCmd current_motion_cmd_;
ScoutLightCmd current_light_cmd_;
// get robot state
ScoutState GetScoutState();
int32_t cmd_thread_period_ms_ = 10;
bool cmd_thread_started_ = false;
private:
// hardware communication interface
std::shared_ptr<ASyncCAN> can_if_;
std::shared_ptr<ASyncSerial> serial_if_;
bool light_ctrl_enabled_ = false;
bool light_ctrl_requested_ = false;
// CAN priority higher than serial if both connected
bool can_connected_ = false;
bool serial_connected_ = 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);
// serial port related variables
uint8_t tx_cmd_len_;
uint8_t tx_buffer_[SCOUT_CMD_BUF_LEN];
void SendMotionCmd(uint8_t count);
void SendLightCmd(uint8_t count);
void NewStatusMsgReceivedCallback(const ScoutMessage &msg);
// cmd/status update related variables
std::thread cmd_thread_;
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_;
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 ScoutMessage &msg);
public:
static void UpdateScoutState(const ScoutMessage &status_msg, ScoutState &state);
public:
static void UpdateScoutState(const ScoutMessage &status_msg,
ScoutState &state);
};
} // namespace westonrobot
} // namespace westonrobot
#endif /* SCOUT_BASE_HPP */