tested timeout

This commit is contained in:
Ruixiang Du
2020-09-15 11:00:16 +08:00
parent 0887261a99
commit a872dd0e0e
5 changed files with 119 additions and 109 deletions

View File

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