more code cleanup

This commit is contained in:
Ruixiang Du
2020-06-17 11:38:29 +08:00
parent 44b89ee5f9
commit 2b9f7cc616
45 changed files with 580 additions and 129 deletions

View File

@@ -1,11 +1,11 @@
/*
/*
* hunter_base.hpp
*
*
* Created on: Apr 01, 2020 09:43
* Description:
*
* Description:
*
* Copyright (c) 2019 Ruixiang Du (rdu)
*/
*/
#ifndef HUNTER_BASE_HPP
#define HUNTER_BASE_HPP
@@ -16,84 +16,88 @@
#include <mutex>
#include <functional>
#include "wrp_sdk/async_io/async_can.hpp"
#include "wrp_sdk/async_io/async_serial.hpp"
#include "wrp_sdk/asyncio/async_can.hpp"
#include "wrp_sdk/asyncio/async_serial.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 wescore
{
class HunterBase
{
public:
HunterBase() = default;
~HunterBase();
namespace westonrobot {
class HunterBase {
public:
HunterBase() = default;
~HunterBase();
// do not allow copy
HunterBase(const HunterBase &hunter) = delete;
HunterBase &operator=(const HunterBase &hunter) = delete;
// 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);
public:
// connect to roboot from CAN
void Connect(std::string dev_name);
// disconnect from roboot, only valid for serial port
void Disconnect();
// 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; };
// 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 steering_angle,
HunterMotionCmd::FaultClearFlag fault_clr_flag = HunterMotionCmd::FaultClearFlag::NO_FAULT);
// motion control
void SetMotionCommand(double linear_vel, double steering_angle,
HunterMotionCmd::FaultClearFlag fault_clr_flag =
HunterMotionCmd::FaultClearFlag::NO_FAULT);
// get robot state
HunterState GetHunterState();
// get robot state
HunterState GetHunterState();
private:
// hardware communication interface
std::shared_ptr<ASyncCAN> can_if_;
std::shared_ptr<ASyncSerial> serial_if_;
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;
// 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];
// 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_;
// 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_;
HunterState hunter_state_;
HunterMotionCmd current_motion_cmd_;
int32_t cmd_thread_period_ms_ = 10;
bool cmd_thread_started_ = false;
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);
// 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 StartCmdThread();
void ControlLoop(int32_t period_ms);
void SendMotionCmd(uint8_t count);
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 ParseCANFrame(can_frame *rx_frame);
void ParseUARTBuffer(uint8_t *buf, const size_t bufsize,
size_t bytes_received);
void NewStatusMsgReceivedCallback(const HunterMessage &msg);
void NewStatusMsgReceivedCallback(const HunterMessage &msg);
public:
static void UpdateHunterState(const HunterMessage &status_msg, HunterState &state);
public:
static void UpdateHunterState(const HunterMessage &status_msg,
HunterState &state);
};
} // namespace wescore
} // namespace westonrobot
#endif /* HUNTER_BASE_HPP */

View File

@@ -13,7 +13,7 @@
#include <cstdint>
#include <iostream>
namespace wescore
namespace westonrobot
{
struct HunterState
{
@@ -69,6 +69,6 @@ struct HunterMotionCmd
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 wescore
} // namespace westonrobot
#endif /* HUNTER_TYPES_HPP */