mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 03:15:01 +08:00
minor update, tested on robot
This commit is contained in:
@@ -22,7 +22,7 @@ int main(int argc, char **argv)
|
||||
ScoutROSMessenger messenger(&robot, node);
|
||||
|
||||
std::string scout_can_port;
|
||||
private_node.param<std::string>("port_name", scout_can_port, std::string("can1"));
|
||||
private_node.param<std::string>("port_name", scout_can_port, std::string("can0"));
|
||||
private_node.param<std::string>("odom_frame", messenger.odom_frame_, std::string("odom"));
|
||||
private_node.param<std::string>("base_frame", messenger.base_frame_, std::string("base_footprint"));
|
||||
private_node.param<bool>("simulated_robot", messenger.simulated_robot_, false);
|
||||
|
||||
@@ -37,13 +37,13 @@ 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
|
||||
{
|
||||
std::lock_guard<std::mutex> guard(twist_mutex_);
|
||||
current_twist_ = *msg.get();
|
||||
}
|
||||
// ROS_INFO("cmd received:%f, %f", msg->linear.x, msg->angular.z);
|
||||
}
|
||||
|
||||
void ScoutROSMessenger::GetCurrentMotionCmdForSim(double &linear, double &angular)
|
||||
|
||||
Reference in New Issue
Block a user