diff --git a/scout_base/launch/scout_base.launch b/scout_base/launch/scout_base.launch index 88a8353..32ca81c 100644 --- a/scout_base/launch/scout_base.launch +++ b/scout_base/launch/scout_base.launch @@ -1,6 +1,6 @@ - + diff --git a/scout_base/src/scout_base_node.cpp b/scout_base/src/scout_base_node.cpp index e87df9e..6f4a919 100644 --- a/scout_base/src/scout_base_node.cpp +++ b/scout_base/src/scout_base_node.cpp @@ -29,6 +29,7 @@ int main(int argc, char **argv) // connect to scout and setup ROS subscription robot.ConnectCANBus(scout_can_port); + robot.StartCmdThread(10); messenger.SetupSubscription(); // publish robot state at 20Hz while listening to twist commands diff --git a/scout_base/src/scout_messenger.cpp b/scout_base/src/scout_messenger.cpp index 35bfa48..f1a7fe4 100644 --- a/scout_base/src/scout_messenger.cpp +++ b/scout_base/src/scout_messenger.cpp @@ -37,6 +37,7 @@ void ScoutROSMessenger::TwistCmdCallback(const geometry_msgs::Twist::ConstPtr &m if (!simulated_robot_) { scout_->SetMotionCommand(msg->linear.x, msg->angular.z); + // ROS_INFO("cmd received:%f, %f", msg->linear.x, msg->angular.z); } else { diff --git a/scout_base/src/scout_sdk/src/demo/demo_scout_can.cpp b/scout_base/src/scout_sdk/src/demo/demo_scout_can.cpp index 0b24be5..53eb197 100644 --- a/scout_base/src/scout_sdk/src/demo/demo_scout_can.cpp +++ b/scout_base/src/scout_sdk/src/demo/demo_scout_can.cpp @@ -14,7 +14,7 @@ using namespace wescore; int main(int argc, char **argv) { ScoutBase scout; - scout.ConnectCANBus("can1"); + scout.ConnectCANBus("can0"); scout.StartCmdThread(10); scout.SetLightCommand({ScoutLightCmd::LightMode::CONST_ON, 0, ScoutLightCmd::LightMode::CONST_ON, 0}); diff --git a/scout_base/src/scout_sdk/src/sdk_core/scout_base/include/scout/scout_base.hpp b/scout_base/src/scout_sdk/src/sdk_core/scout_base/include/scout/scout_base.hpp index 1575a89..3b35da1 100644 --- a/scout_base/src/scout_sdk/src/sdk_core/scout_base/include/scout/scout_base.hpp +++ b/scout_base/src/scout_sdk/src/sdk_core/scout_base/include/scout/scout_base.hpp @@ -40,7 +40,7 @@ public: // motion control void SetMotionCommand(double linear_vel, double angular_vel, ScoutMotionCmd::FaultClearFlag fault_clr_flag = ScoutMotionCmd::FaultClearFlag::NO_FAULT); - + // light control void SetLightCommand(ScoutLightCmd cmd); void DisableLightCmdControl(); @@ -63,6 +63,8 @@ private: ScoutMotionCmd current_motion_cmd_; ScoutLightCmd current_light_cmd_; + bool cmd_thread_started_ = false; + bool light_ctrl_enabled_ = false; bool light_ctrl_requested_ = false; diff --git a/scout_base/src/scout_sdk/src/sdk_core/scout_base/src/scout_base.cpp b/scout_base/src/scout_sdk/src/sdk_core/scout_base/src/scout_base.cpp index 456bbbc..bd95cf9 100644 --- a/scout_base/src/scout_sdk/src/sdk_core/scout_base/src/scout_base.cpp +++ b/scout_base/src/scout_sdk/src/sdk_core/scout_base/src/scout_base.cpp @@ -93,6 +93,7 @@ void ScoutBase::ConnectCANBus(const std::string &can_if_name) void ScoutBase::StartCmdThread(int32_t period_ms) { cmd_thread_ = std::thread(std::bind(&ScoutBase::ControlLoop, this, period_ms)); + cmd_thread_started_ = true; } void ScoutBase::ControlLoop(int32_t period_ms) @@ -180,6 +181,10 @@ ScoutState ScoutBase::GetScoutState() void ScoutBase::SetMotionCommand(double linear_vel, double angular_vel, ScoutMotionCmd::FaultClearFlag fault_clr_flag) { + // make sure cmd thread is started before attempting to send commands + if (!cmd_thread_started_) + StartCmdThread(10); + if (linear_vel < ScoutMotionCmd::min_linear_velocity) linear_vel = ScoutMotionCmd::min_linear_velocity; if (linear_vel > ScoutMotionCmd::max_linear_velocity) diff --git a/scout_robot/package.xml b/scout_robot/package.xml index 3e4c8e6..e454cd2 100644 --- a/scout_robot/package.xml +++ b/scout_robot/package.xml @@ -4,7 +4,7 @@ 0.3.3 Metapackage for AgileX Scout robot software - Ruixiang Du + Ruixiang Du BSD @@ -15,7 +15,6 @@ catkin scout_bringup scout_base - scout_msgs