saved work

This commit is contained in:
Ruixiang Du
2020-06-17 14:47:37 +08:00
parent 741c521863
commit 19197facc0
5 changed files with 52 additions and 184 deletions

View File

@@ -17,7 +17,6 @@
#include <cstdint>
#include <thread>
#include <mutex>
#include <functional>
#include "wrp_sdk/asyncio/async_can.hpp"
#include "wrp_sdk/asyncio/async_serial.hpp"
@@ -64,10 +63,11 @@ class MobileBase {
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) = 0;
virtual void ParseCANFrame(can_frame *rx_frame){};
virtual void ParseUARTBuffer(uint8_t *buf, const size_t bufsize,
size_t bytes_received) = 0;
size_t bytes_received){};
};
} // namespace westonrobot

View File

@@ -14,84 +14,50 @@
#include <cstdint>
#include <thread>
#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/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 {
class HunterBase : public MobileBase {
public:
HunterBase() = default;
~HunterBase();
HunterBase() : MobileBase(){};
~HunterBase() = default;
// do not allow copy
HunterBase(const HunterBase &hunter) = delete;
HunterBase &operator=(const HunterBase &hunter) = 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;
};
// get robot state
HunterState GetHunterState();
// motion control
void SetMotionCommand(double linear_vel, double steering_angle,
HunterMotionCmd::FaultClearFlag fault_clr_flag =
HunterMotionCmd::FaultClearFlag::NO_FAULT);
// get robot state
HunterState GetHunterState();
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_[HUNTER_CMD_BUF_LEN];
// cmd/status update related variables
std::thread cmd_thread_;
std::mutex hunter_state_mutex_;
std::mutex motion_cmd_mutex_;
HunterState hunter_state_;
HunterMotionCmd current_motion_cmd_;
int32_t cmd_thread_period_ms_ = 10;
bool cmd_thread_started_ = 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 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 ParseCANFrame(can_frame *rx_frame);
void ParseUARTBuffer(uint8_t *buf, const size_t bufsize,
size_t bytes_received);
void NewStatusMsgReceivedCallback(const HunterMessage &msg);
public: