mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 11:20:02 +08:00
tested on scout
This commit is contained in:
@@ -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
|
||||
|
||||
@@ -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
|
||||
{
|
||||
|
||||
@@ -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});
|
||||
|
||||
@@ -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;
|
||||
|
||||
|
||||
@@ -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)
|
||||
|
||||
Reference in New Issue
Block a user