mirror of
https://github.com/westonrobot/ugv_sdk
synced 2023-04-08 06:32:14 +08:00
saved work on cmd timeout, not finished yet
This commit is contained in:
@@ -31,6 +31,8 @@ class MobileBase {
|
|||||||
MobileBase(const MobileBase &hunter) = delete;
|
MobileBase(const MobileBase &hunter) = delete;
|
||||||
MobileBase &operator=(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
|
// connect to roboot from CAN or serial
|
||||||
void Connect(std::string dev_name, int32_t baud_rate = 0);
|
void Connect(std::string dev_name, int32_t baud_rate = 0);
|
||||||
|
|
||||||
@@ -50,6 +52,12 @@ class MobileBase {
|
|||||||
std::shared_ptr<AsyncCAN> can_if_;
|
std::shared_ptr<AsyncCAN> can_if_;
|
||||||
std::shared_ptr<AsyncSerial> serial_if_;
|
std::shared_ptr<AsyncSerial> serial_if_;
|
||||||
|
|
||||||
|
// timeout to be implemented in each vehicle
|
||||||
|
bool enable_timeout_ = true;
|
||||||
|
uint32_t timeout_ms_ = 100;
|
||||||
|
uint32_t watchdog_counter_ = 0;
|
||||||
|
virtual void CheckCmdTimeout();
|
||||||
|
|
||||||
// command thread
|
// command thread
|
||||||
std::thread cmd_thread_;
|
std::thread cmd_thread_;
|
||||||
int32_t cmd_thread_period_ms_ = 10;
|
int32_t cmd_thread_period_ms_ = 10;
|
||||||
|
|||||||
@@ -67,7 +67,6 @@ void MobileBase::StartCmdThread() {
|
|||||||
void MobileBase::ControlLoop(int32_t period_ms) {
|
void MobileBase::ControlLoop(int32_t period_ms) {
|
||||||
StopWatch ctrl_sw;
|
StopWatch ctrl_sw;
|
||||||
bool print_loop_freq = false;
|
bool print_loop_freq = false;
|
||||||
static uint32_t iter_cnt = 0;
|
|
||||||
while (true) {
|
while (true) {
|
||||||
ctrl_sw.tic();
|
ctrl_sw.tic();
|
||||||
SendRobotCmd();
|
SendRobotCmd();
|
||||||
|
|||||||
Reference in New Issue
Block a user