updated ros wrapper to work with can sdk

This commit is contained in:
Ruixiang Du
2019-06-14 11:10:51 -04:00
parent 7807b33529
commit 48037d0d88
4417 changed files with 628441 additions and 8525 deletions

View File

@@ -0,0 +1,43 @@
#include <string>
#include <boost/thread.hpp>
#include <ros/ros.h>
#include <sensor_msgs/JointState.h>
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>
#include "scout/scout_base.hpp"
#include "scout_base/scout_messenger.hpp"
using namespace wescore;
int main(int argc, char **argv)
{
// setup ROS node
ros::init(argc, argv, "scout_odom");
ros::NodeHandle node("scout_robot"), private_node("~");
// instantiate a robot
ScoutBase robot;
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>("odom_frame_", messenger.odom_frame_, std::string("odom"));
private_node.param<std::string>("base_frame_", messenger.base_frame_, std::string("base_footprint"));
// connect to scout and setup ROS subscription
robot.ConnectCANBus(scout_can_port);
messenger.SetupSubscription();
// publish robot state at 20Hz while listening to twist commands
ros::Rate rt(20); // 20Hz
while (true)
{
messenger.PublishStateToROS();
ros::spinOnce();
rt.sleep();
}
return 0;
}