This commit is contained in:
Ruixiang Du
2020-09-18 13:36:06 +08:00
9 changed files with 155 additions and 111 deletions

View File

@@ -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 < 100) {
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;
}

View File

@@ -54,6 +54,8 @@ short CursorColor(int fg)
return (COLOR_YELLOW);
case 7: /* 111 */
return (COLOR_WHITE);
default:
return COLOR_BLACK;
}
}
} // namespace

View File

@@ -23,7 +23,7 @@ class AsyncSerial : public AsyncListener,
public std::enable_shared_from_this<AsyncSerial> {
public:
using ReceiveCallback =
std::function<void(uint8_t *data, size_t len, const size_t bufsize)>;
std::function<void(uint8_t *data, const size_t bufsize, size_t len)>;
public:
AsyncSerial(std::string port_name, uint32_t baud_rate = 115200);
@@ -56,7 +56,7 @@ class AsyncSerial : public AsyncListener,
bool tx_in_progress_ = false;
bool SetupPort();
void DefaultReceiveCallback(uint8_t *data, size_t len, const size_t bufsize);
void DefaultReceiveCallback(uint8_t *data, const size_t bufsize, size_t len);
void ReadFromPort();
void WriteToPort(bool check_if_busy);
};

View File

@@ -31,6 +31,8 @@ class MobileBase {
MobileBase(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
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<AsyncSerial> serial_if_;
// timeout to be implemented in each vehicle
bool enable_timeout_ = true;
uint32_t timeout_ms_ = 500;
uint32_t watchdog_counter_ = 0;
void FeedCmdTimeoutWatchdog() { watchdog_counter_ = 0; };
// command thread
std::thread cmd_thread_;
int32_t cmd_thread_period_ms_ = 10;

View File

@@ -107,7 +107,7 @@ void AsyncCAN::SendFrame(const can_frame &frame) {
asio::buffer(&frame, sizeof(frame)),
[](asio::error_code error, size_t bytes_transferred) {
if (error) {
std::cerr << "Failed to send CAN frame";
std::cerr << "Failed to send CAN frame" << std::endl;
}
// std::cout << "frame sent" << std::endl;
});

View File

@@ -80,8 +80,8 @@ void AsyncSerial::StopService() {
port_opened_ = false;
}
void AsyncSerial::DefaultReceiveCallback(uint8_t *data, size_t len,
const size_t bufsize) {}
void AsyncSerial::DefaultReceiveCallback(uint8_t *data, const size_t bufsize,
size_t len) {}
void AsyncSerial::ReadFromPort() {
auto sthis = shared_from_this();
@@ -93,9 +93,13 @@ void AsyncSerial::ReadFromPort() {
return;
}
if (sthis->rcv_cb_ != nullptr)
sthis->rcv_cb_(sthis->rx_buf_.data(), bytes_transferred,
sthis->rx_buf_.size());
if (sthis->rcv_cb_ != nullptr) {
sthis->rcv_cb_(sthis->rx_buf_.data(), sthis->rx_buf_.size(),
bytes_transferred);
} else {
sthis->DefaultReceiveCallback(
sthis->rx_buf_.data(), sthis->rx_buf_.size(), bytes_transferred);
}
sthis->ReadFromPort();
});
}

View File

@@ -80,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) {

View File

@@ -34,6 +34,7 @@ void MobileBase::Connect(std::string dev_name, int32_t baud_rate) {
}
void MobileBase::Disconnect() {
if (can_connected_) can_if_->StopService();
if (serial_connected_ && serial_if_->IsOpened()) {
serial_if_->StopService();
}
@@ -43,7 +44,7 @@ void MobileBase::ConfigureCAN(const std::string &can_if_name) {
can_if_ = std::make_shared<AsyncCAN>(can_if_name);
can_if_->SetReceiveCallback(
std::bind(&MobileBase::ParseCANFrame, this, std::placeholders::_1));
serial_if_->StartListening();
can_if_->StartListening();
can_connected_ = true;
}
@@ -66,9 +67,26 @@ void MobileBase::StartCmdThread() {
void MobileBase::ControlLoop(int32_t period_ms) {
StopWatch ctrl_sw;
bool print_loop_freq = false;
uint32_t timeout_iter_num;
if (enable_timeout_) {
if (timeout_ms_ < period_ms) timeout_ms_ = 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();
SendRobotCmd();
if (enable_timeout_) {
if (watchdog_counter_ < timeout_iter_num) {
SendRobotCmd();
++watchdog_counter_;
} else {
std::cout << "Warning: cmd timeout, old cmd not sent to robot" << std::endl;
}
} else {
SendRobotCmd();
}
ctrl_sw.sleep_until_ms(period_ms);
if (print_loop_freq)
std::cout << "control loop frequency: " << 1.0 / ctrl_sw.toc()

View File

@@ -55,10 +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;
} 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;
}
}
@@ -158,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) {