tested on scout

This commit is contained in:
Ruixiang Du
2019-07-08 23:36:02 -04:00
parent f0e9fc6f44
commit 3d72694f3a
7 changed files with 13 additions and 5 deletions

View File

@@ -1,6 +1,6 @@
<launch> <launch>
<node name="scout_odom" pkg="scout_base" type="scout_base_node" output="screen"> <node name="scout_odom" pkg="scout_base" type="scout_base_node" output="screen">
<param name="port_name" type="string" value="can1" /> <param name="port_name" type="string" value="can0" />
<param name="odom_frame" type="string" value="odom" /> <param name="odom_frame" type="string" value="odom" />
<param name="base_frame" type="string" value="base_footprint" /> <param name="base_frame" type="string" value="base_footprint" />

View File

@@ -29,6 +29,7 @@ int main(int argc, char **argv)
// connect to scout and setup ROS subscription // connect to scout and setup ROS subscription
robot.ConnectCANBus(scout_can_port); robot.ConnectCANBus(scout_can_port);
robot.StartCmdThread(10);
messenger.SetupSubscription(); messenger.SetupSubscription();
// publish robot state at 20Hz while listening to twist commands // publish robot state at 20Hz while listening to twist commands

View File

@@ -37,6 +37,7 @@ void ScoutROSMessenger::TwistCmdCallback(const geometry_msgs::Twist::ConstPtr &m
if (!simulated_robot_) if (!simulated_robot_)
{ {
scout_->SetMotionCommand(msg->linear.x, msg->angular.z); scout_->SetMotionCommand(msg->linear.x, msg->angular.z);
// ROS_INFO("cmd received:%f, %f", msg->linear.x, msg->angular.z);
} }
else else
{ {

View File

@@ -14,7 +14,7 @@ using namespace wescore;
int main(int argc, char **argv) int main(int argc, char **argv)
{ {
ScoutBase scout; ScoutBase scout;
scout.ConnectCANBus("can1"); scout.ConnectCANBus("can0");
scout.StartCmdThread(10); scout.StartCmdThread(10);
scout.SetLightCommand({ScoutLightCmd::LightMode::CONST_ON, 0, ScoutLightCmd::LightMode::CONST_ON, 0}); scout.SetLightCommand({ScoutLightCmd::LightMode::CONST_ON, 0, ScoutLightCmd::LightMode::CONST_ON, 0});

View File

@@ -40,7 +40,7 @@ public:
// motion control // motion control
void SetMotionCommand(double linear_vel, double angular_vel, void SetMotionCommand(double linear_vel, double angular_vel,
ScoutMotionCmd::FaultClearFlag fault_clr_flag = ScoutMotionCmd::FaultClearFlag::NO_FAULT); ScoutMotionCmd::FaultClearFlag fault_clr_flag = ScoutMotionCmd::FaultClearFlag::NO_FAULT);
// light control // light control
void SetLightCommand(ScoutLightCmd cmd); void SetLightCommand(ScoutLightCmd cmd);
void DisableLightCmdControl(); void DisableLightCmdControl();
@@ -63,6 +63,8 @@ private:
ScoutMotionCmd current_motion_cmd_; ScoutMotionCmd current_motion_cmd_;
ScoutLightCmd current_light_cmd_; ScoutLightCmd current_light_cmd_;
bool cmd_thread_started_ = false;
bool light_ctrl_enabled_ = false; bool light_ctrl_enabled_ = false;
bool light_ctrl_requested_ = false; bool light_ctrl_requested_ = false;

View File

@@ -93,6 +93,7 @@ void ScoutBase::ConnectCANBus(const std::string &can_if_name)
void ScoutBase::StartCmdThread(int32_t period_ms) void ScoutBase::StartCmdThread(int32_t period_ms)
{ {
cmd_thread_ = std::thread(std::bind(&ScoutBase::ControlLoop, this, period_ms)); cmd_thread_ = std::thread(std::bind(&ScoutBase::ControlLoop, this, period_ms));
cmd_thread_started_ = true;
} }
void ScoutBase::ControlLoop(int32_t period_ms) 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) 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) if (linear_vel < ScoutMotionCmd::min_linear_velocity)
linear_vel = ScoutMotionCmd::min_linear_velocity; linear_vel = ScoutMotionCmd::min_linear_velocity;
if (linear_vel > ScoutMotionCmd::max_linear_velocity) if (linear_vel > ScoutMotionCmd::max_linear_velocity)

View File

@@ -4,7 +4,7 @@
<version>0.3.3</version> <version>0.3.3</version>
<description>Metapackage for AgileX Scout robot software</description> <description>Metapackage for AgileX Scout robot software</description>
<maintainer email="ruixiang.du@westonrobot.com">Ruixiang Du</maintainer> <maintainer email="ruixiang.du@gmail.com">Ruixiang Du</maintainer>
<license>BSD</license> <license>BSD</license>
@@ -15,7 +15,6 @@
<buildtool_depend>catkin</buildtool_depend> <buildtool_depend>catkin</buildtool_depend>
<run_depend>scout_bringup</run_depend> <run_depend>scout_bringup</run_depend>
<run_depend>scout_base</run_depend> <run_depend>scout_base</run_depend>
<run_depend>scout_msgs</run_depend>
<export> <export>
<metapackage/> <metapackage/>