#include #include #include #include #include #include "scout_base/scout_messenger.hpp" #include "scout_sdk/scout_base.hpp" using namespace wescore; int main(int argc, char **argv) { // setup ROS node ros::init(argc, argv, "scout_odom"); ros::NodeHandle node(""), private_node("~"); // instantiate a robot object ScoutBase robot; ScoutROSMessenger messenger(&robot, &node); // fetch parameters before connecting to robot std::string port_name; private_node.param("port_name", port_name, 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_link")); private_node.param("simulated_robot", messenger.simulated_robot_, false); private_node.param("control_rate", messenger.sim_control_rate_, 50); if (!messenger.simulated_robot_) { // connect to robot and setup ROS subscription if (port_name.find("can") != std::string::npos) { robot.Connect(port_name); ROS_INFO("Using CAN bus to talk with the robot"); } else { robot.Connect(port_name, 115200); ROS_INFO("Using UART to talk with the robot"); } } messenger.SetupSubscription(); // publish robot state at 50Hz while listening to twist commands ros::Rate rate(50); while (true) { if (!messenger.simulated_robot_) { messenger.PublishStateToROS(); } else { double linear, angular; messenger.GetCurrentMotionCmdForSim(linear, angular); messenger.PublishSimStateToROS(linear, angular); } ros::spinOnce(); rate.sleep(); } return 0; }