diff --git a/scout_base/src/scout_base_node.cpp b/scout_base/src/scout_base_node.cpp index 7e6175d..7264918 100644 --- a/scout_base/src/scout_base_node.cpp +++ b/scout_base/src/scout_base_node.cpp @@ -22,7 +22,7 @@ int main(int argc, char **argv) ScoutROSMessenger messenger(&robot, node); std::string scout_can_port; - private_node.param("port_name", scout_can_port, std::string("can1")); + private_node.param("port_name", scout_can_port, std::string("can0")); private_node.param("odom_frame", messenger.odom_frame_, std::string("odom")); private_node.param("base_frame", messenger.base_frame_, std::string("base_footprint")); private_node.param("simulated_robot", messenger.simulated_robot_, false); diff --git a/scout_base/src/scout_messenger.cpp b/scout_base/src/scout_messenger.cpp index f1a7fe4..8d32f2d 100644 --- a/scout_base/src/scout_messenger.cpp +++ b/scout_base/src/scout_messenger.cpp @@ -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 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)