Merge branch 'bugfix-odometry_with_estop_activated' into 'v2.x'

Bugfix odometry with estop activated

See merge request westonrobot/ros/scout_base!7
This commit is contained in:
Ruixiang Du
2021-05-18 10:03:44 +00:00
2 changed files with 7 additions and 2 deletions

View File

@@ -11,12 +11,17 @@
using namespace westonrobot;
std::shared_ptr<ScoutBase> robot;
bool keep_run = true;
void DetachRobot(int signal) { keep_run = false; }
int main(int argc, char **argv) {
// setup ROS node
ros::init(argc, argv, "scout_node");
ros::NodeHandle node(""), private_node("~");
std::signal(SIGINT, DetachRobot);
// instantiate a robot object
robot = std::make_shared<ScoutBase>();
ScoutROSMessenger messenger(robot.get(), &node);
@@ -46,7 +51,7 @@ int main(int argc, char **argv) {
// publish robot state at 50Hz while listening to twist commands
ros::Rate rate(50);
while (true) {
while (keep_run) {
if (!messenger.simulated_robot_) {
messenger.PublishStateToROS();
} else {

View File

@@ -276,7 +276,7 @@ namespace westonrobot
// publish odometry and tf messages
nav_msgs::Odometry odom_msg;
odom_msg.header.stamp = current_time_;
odom_msg.header.frame_id = "testes";
odom_msg.header.frame_id = odom_frame_;
odom_msg.child_frame_id = base_frame_;
odom_msg.pose.pose.position.x = position_x_;