mirror of
https://github.com/westonrobot/ugv_sdk
synced 2023-04-08 06:32:14 +08:00
tested timeout
This commit is contained in:
@@ -1,9 +1,9 @@
|
||||
/*
|
||||
/*
|
||||
* demo_scout_can.cpp
|
||||
*
|
||||
*
|
||||
* Created on: Jun 12, 2019 05:03
|
||||
* Description:
|
||||
*
|
||||
* Description:
|
||||
*
|
||||
* Copyright (c) 2019 Ruixiang Du (rdu)
|
||||
*/
|
||||
|
||||
@@ -11,106 +11,112 @@
|
||||
|
||||
using namespace westonrobot;
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
std::string device_name;
|
||||
int32_t baud_rate = 0;
|
||||
int main(int argc, char **argv) {
|
||||
std::string device_name;
|
||||
int32_t baud_rate = 0;
|
||||
|
||||
if (argc == 2)
|
||||
{
|
||||
device_name = {argv[1]};
|
||||
std::cout << "Specified CAN: " << device_name << std::endl;
|
||||
}
|
||||
else if (argc == 3)
|
||||
{
|
||||
device_name = {argv[1]};
|
||||
baud_rate = std::stol(argv[2]);
|
||||
std::cout << "Specified serial: " << device_name << "@" << baud_rate << std::endl;
|
||||
}
|
||||
else
|
||||
{
|
||||
std::cout << "Usage: app_scout_demo <interface>" << std::endl
|
||||
<< "Example 1: ./app_scout_demo can0" << std::endl
|
||||
<< "Example 2: ./app_scout_demo /dev/ttyUSB0 115200" << std::endl;
|
||||
return -1;
|
||||
if (argc == 2) {
|
||||
device_name = {argv[1]};
|
||||
std::cout << "Specified CAN: " << device_name << std::endl;
|
||||
} else if (argc == 3) {
|
||||
device_name = {argv[1]};
|
||||
baud_rate = std::stol(argv[2]);
|
||||
std::cout << "Specified serial: " << device_name << "@" << baud_rate
|
||||
<< std::endl;
|
||||
} else {
|
||||
std::cout << "Usage: app_scout_demo <interface>" << std::endl
|
||||
<< "Example 1: ./app_scout_demo can0" << std::endl
|
||||
<< "Example 2: ./app_scout_demo /dev/ttyUSB0 115200" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
ScoutBase scout;
|
||||
scout.Connect(device_name, baud_rate);
|
||||
|
||||
// // light control
|
||||
// std::cout << "Light: const off" << std::endl;
|
||||
// scout.SetLightCommand({ScoutLightCmd::LightMode::CONST_OFF, 0,
|
||||
// ScoutLightCmd::LightMode::CONST_OFF, 0});
|
||||
// sleep(3);
|
||||
// std::cout << "Light: const on" << std::endl;
|
||||
// scout.SetLightCommand({ScoutLightCmd::LightMode::CONST_ON, 0,
|
||||
// ScoutLightCmd::LightMode::CONST_ON, 0});
|
||||
// sleep(3);
|
||||
// std::cout << "Light: breath" << std::endl;
|
||||
// scout.SetLightCommand({ScoutLightCmd::LightMode::BREATH, 0,
|
||||
// ScoutLightCmd::LightMode::BREATH, 0});
|
||||
// sleep(3);
|
||||
// std::cout << "Light: custom 90-80" << std::endl;
|
||||
// scout.SetLightCommand({ScoutLightCmd::LightMode::CUSTOM, 90,
|
||||
// ScoutLightCmd::LightMode::CUSTOM, 80});
|
||||
// sleep(3);
|
||||
// std::cout << "Light: diabled cmd control" << std::endl;
|
||||
// scout.DisableLightCmdControl();
|
||||
|
||||
int count = 0;
|
||||
while (true) {
|
||||
// motion control
|
||||
// if (count < 5)
|
||||
// {
|
||||
// std::cout << "Motor: 0.2, 0" << std::endl;
|
||||
// scout.SetMotionCommand(0.2, 0.0);
|
||||
// }
|
||||
// else if (count < 10)
|
||||
// {
|
||||
// std::cout << "Motor: 0.8, 0" << std::endl;
|
||||
// scout.SetMotionCommand(0.8, 0.0);
|
||||
// }
|
||||
// else if (count < 15)
|
||||
// {
|
||||
// std::cout << "Motor: 1.5, 0" << std::endl;
|
||||
// scout.SetMotionCommand(1.5, 0.0);
|
||||
// }
|
||||
// else if (count < 20)
|
||||
// {
|
||||
// std::cout << "Motor: 1.0, 0.5" << std::endl;
|
||||
// scout.SetMotionCommand(1.0, 0.5);
|
||||
// }
|
||||
// else if (count < 25)
|
||||
// {
|
||||
// std::cout << "Motor: 0.0, 0" << std::endl;
|
||||
// scout.SetMotionCommand(0.0, 0.0);
|
||||
// }
|
||||
// else if (count < 30)
|
||||
// {
|
||||
// std::cout << "Motor: -0.5, 0" << std::endl;
|
||||
// scout.SetMotionCommand(-0.5, 0.0);
|
||||
// }
|
||||
// else if (count < 35)
|
||||
// {
|
||||
// std::cout << "Motor: -1.0, -0.5" << std::endl;
|
||||
// scout.SetMotionCommand(-1.0, -0.5);
|
||||
// }
|
||||
// else if (count < 40)
|
||||
// {
|
||||
// std::cout << "Motor: 0.0, 0, Light: breath" << std::endl;
|
||||
// scout.SetMotionCommand(0.0, 0.0);
|
||||
// scout.SetLightCommand({ScoutLightCmd::LightMode::BREATH, 0,
|
||||
// ScoutLightCmd::LightMode::BREATH, 0});
|
||||
// }
|
||||
if (count < 250) {
|
||||
std::cout << "Motor: 0.2, 0" << std::endl;
|
||||
scout.SetMotionCommand(0.2, 0.0);
|
||||
}
|
||||
|
||||
ScoutBase scout;
|
||||
scout.Connect(device_name, baud_rate);
|
||||
auto state = scout.GetScoutState();
|
||||
std::cout << "-------------------------------" << std::endl;
|
||||
std::cout << "count: " << count << std::endl;
|
||||
std::cout << "control mode: " << static_cast<int>(state.control_mode)
|
||||
<< " , base state: " << static_cast<int>(state.base_state)
|
||||
<< std::endl;
|
||||
std::cout << "battery voltage: " << state.battery_voltage << std::endl;
|
||||
std::cout << "velocity (linear, angular): " << state.linear_velocity << ", "
|
||||
<< state.angular_velocity << std::endl;
|
||||
std::cout << "-------------------------------" << std::endl;
|
||||
|
||||
// light control
|
||||
std::cout << "Light: const off" << std::endl;
|
||||
scout.SetLightCommand({ScoutLightCmd::LightMode::CONST_OFF, 0, ScoutLightCmd::LightMode::CONST_OFF, 0});
|
||||
sleep(3);
|
||||
std::cout << "Light: const on" << std::endl;
|
||||
scout.SetLightCommand({ScoutLightCmd::LightMode::CONST_ON, 0, ScoutLightCmd::LightMode::CONST_ON, 0});
|
||||
sleep(3);
|
||||
std::cout << "Light: breath" << std::endl;
|
||||
scout.SetLightCommand({ScoutLightCmd::LightMode::BREATH, 0, ScoutLightCmd::LightMode::BREATH, 0});
|
||||
sleep(3);
|
||||
std::cout << "Light: custom 90-80" << std::endl;
|
||||
scout.SetLightCommand({ScoutLightCmd::LightMode::CUSTOM, 90, ScoutLightCmd::LightMode::CUSTOM, 80});
|
||||
sleep(3);
|
||||
std::cout << "Light: diabled cmd control" << std::endl;
|
||||
scout.DisableLightCmdControl();
|
||||
usleep(20000);
|
||||
++count;
|
||||
}
|
||||
|
||||
int count = 0;
|
||||
while (true)
|
||||
{
|
||||
// motion control
|
||||
if (count < 5)
|
||||
{
|
||||
std::cout << "Motor: 0.2, 0" << std::endl;
|
||||
scout.SetMotionCommand(0.2, 0.0);
|
||||
}
|
||||
else if (count < 10)
|
||||
{
|
||||
std::cout << "Motor: 0.8, 0" << std::endl;
|
||||
scout.SetMotionCommand(0.8, 0.0);
|
||||
}
|
||||
else if (count < 15)
|
||||
{
|
||||
std::cout << "Motor: 1.5, 0" << std::endl;
|
||||
scout.SetMotionCommand(1.5, 0.0);
|
||||
}
|
||||
else if (count < 20)
|
||||
{
|
||||
std::cout << "Motor: 1.0, 0.5" << std::endl;
|
||||
scout.SetMotionCommand(1.0, 0.5);
|
||||
}
|
||||
else if (count < 25)
|
||||
{
|
||||
std::cout << "Motor: 0.0, 0" << std::endl;
|
||||
scout.SetMotionCommand(0.0, 0.0);
|
||||
}
|
||||
else if (count < 30)
|
||||
{
|
||||
std::cout << "Motor: -0.5, 0" << std::endl;
|
||||
scout.SetMotionCommand(-0.5, 0.0);
|
||||
}
|
||||
else if (count < 35)
|
||||
{
|
||||
std::cout << "Motor: -1.0, -0.5" << std::endl;
|
||||
scout.SetMotionCommand(-1.0, -0.5);
|
||||
}
|
||||
else if (count < 40)
|
||||
{
|
||||
std::cout << "Motor: 0.0, 0, Light: breath" << std::endl;
|
||||
scout.SetMotionCommand(0.0, 0.0);
|
||||
scout.SetLightCommand({ScoutLightCmd::LightMode::BREATH, 0, ScoutLightCmd::LightMode::BREATH, 0});
|
||||
}
|
||||
|
||||
auto state = scout.GetScoutState();
|
||||
std::cout << "-------------------------------" << std::endl;
|
||||
std::cout << "count: " << count << std::endl;
|
||||
std::cout << "control mode: " << static_cast<int>(state.control_mode) << " , base state: " << static_cast<int>(state.base_state) << std::endl;
|
||||
std::cout << "battery voltage: " << state.battery_voltage << std::endl;
|
||||
std::cout << "velocity (linear, angular): " << state.linear_velocity << ", " << state.angular_velocity << std::endl;
|
||||
std::cout << "-------------------------------" << std::endl;
|
||||
|
||||
sleep(1);
|
||||
++count;
|
||||
}
|
||||
|
||||
return 0;
|
||||
return 0;
|
||||
}
|
||||
@@ -54,7 +54,7 @@ class MobileBase {
|
||||
|
||||
// timeout to be implemented in each vehicle
|
||||
bool enable_timeout_ = true;
|
||||
uint32_t timeout_ms_ = 100;
|
||||
uint32_t timeout_ms_ = 500;
|
||||
uint32_t watchdog_counter_ = 0;
|
||||
void FeedCmdTimeoutWatchdog() { watchdog_counter_ = 0; };
|
||||
|
||||
|
||||
@@ -17,7 +17,6 @@ namespace westonrobot {
|
||||
void HunterBase::SendRobotCmd() {
|
||||
static uint8_t cmd_count = 0;
|
||||
SendMotionCmd(cmd_count++);
|
||||
FeedCmdTimeoutWatchdog();
|
||||
}
|
||||
|
||||
void HunterBase::SendMotionCmd(uint8_t count) {
|
||||
@@ -81,6 +80,8 @@ void HunterBase::SetMotionCommand(
|
||||
current_motion_cmd_.angular_velocity = static_cast<int8_t>(
|
||||
steering_angle / HunterMotionCmd::max_steering_angle * 100.0);
|
||||
current_motion_cmd_.fault_clear_flag = fault_clr_flag;
|
||||
|
||||
FeedCmdTimeoutWatchdog();
|
||||
}
|
||||
|
||||
void HunterBase::ParseCANFrame(can_frame *rx_frame) {
|
||||
|
||||
@@ -74,14 +74,16 @@ void MobileBase::ControlLoop(int32_t period_ms) {
|
||||
timeout_iter_num = static_cast<uint32_t>(timeout_ms_ / period_ms);
|
||||
std::cout << "Timeout iteration number: " << timeout_iter_num << std::endl;
|
||||
}
|
||||
|
||||
while (true) {
|
||||
ctrl_sw.tic();
|
||||
if (enable_timeout_) {
|
||||
++watchdog_counter_;
|
||||
if (watchdog_counter_ < timeout_iter_num)
|
||||
if (watchdog_counter_ < timeout_iter_num) {
|
||||
SendRobotCmd();
|
||||
else
|
||||
++watchdog_counter_;
|
||||
} else {
|
||||
std::cout << "Warning: cmd timeout, not sent to robot" << std::endl;
|
||||
}
|
||||
} else {
|
||||
SendRobotCmd();
|
||||
}
|
||||
|
||||
@@ -18,7 +18,6 @@ void ScoutBase::SendRobotCmd() {
|
||||
static uint8_t light_cmd_count = 0;
|
||||
SendMotionCmd(cmd_count++);
|
||||
if (light_ctrl_requested_) SendLightCmd(light_cmd_count++);
|
||||
FeedCmdTimeoutWatchdog();
|
||||
}
|
||||
|
||||
void ScoutBase::SendMotionCmd(uint8_t count) {
|
||||
@@ -56,12 +55,12 @@ void ScoutBase::SendMotionCmd(uint8_t count) {
|
||||
can_frame m_frame;
|
||||
EncodeScoutMsgToCAN(&m_msg, &m_frame);
|
||||
can_if_->SendFrame(m_frame);
|
||||
std::cout << "CAN cmd sent" << std::endl;
|
||||
// std::cout << "CAN cmd sent" << std::endl;
|
||||
} else {
|
||||
// send to serial port
|
||||
EncodeScoutMsgToUART(&m_msg, tx_buffer_, &tx_cmd_len_);
|
||||
serial_if_->SendBytes(tx_buffer_, tx_cmd_len_);
|
||||
std::cout << "serial cmd sent" << std::endl;
|
||||
// std::cout << "serial cmd sent" << std::endl;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -161,6 +160,8 @@ void ScoutBase::SetMotionCommand(
|
||||
current_motion_cmd_.angular_velocity = static_cast<int8_t>(
|
||||
angular_vel / ScoutMotionCmd::max_angular_velocity * 100.0);
|
||||
current_motion_cmd_.fault_clear_flag = fault_clr_flag;
|
||||
|
||||
FeedCmdTimeoutWatchdog();
|
||||
}
|
||||
|
||||
void ScoutBase::SetLightCommand(ScoutLightCmd cmd) {
|
||||
|
||||
Reference in New Issue
Block a user