major revision

This commit is contained in:
Ruixiang Du
2019-07-08 22:24:51 -04:00
parent 6f5b7087a2
commit 727b0a2b05
97 changed files with 5058 additions and 832 deletions

View File

@@ -19,12 +19,13 @@ int main(int argc, char **argv)
// instantiate a robot
ScoutBase robot;
ScoutROSMessenger messenger(robot, node);
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"));
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"));
private_node.param<bool>("simulated_robot", messenger.simulated_robot_, false);
// connect to scout and setup ROS subscription
robot.ConnectCANBus(scout_can_port);