minor update, tested on robot

This commit is contained in:
Ruixiang Du
2019-09-17 23:09:32 -04:00
parent 2ad6f201d2
commit d3b083b386
2 changed files with 2 additions and 2 deletions

View File

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

View File

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