diff --git a/scout_base/include/scout_base/scout_messenger.hpp b/scout_base/include/scout_base/scout_messenger.hpp
index 498e381..a659546 100644
--- a/scout_base/include/scout_base/scout_messenger.hpp
+++ b/scout_base/include/scout_base/scout_messenger.hpp
@@ -30,6 +30,7 @@ public:
std::string odom_frame_;
std::string base_frame_;
+ std::string odom_topic_name_;
bool simulated_robot_ = false;
int sim_control_rate_ = 50;
diff --git a/scout_base/launch/scout_base.launch b/scout_base/launch/scout_base.launch
index a860415..51a1c3d 100644
--- a/scout_base/launch/scout_base.launch
+++ b/scout_base/launch/scout_base.launch
@@ -11,7 +11,8 @@
-->
- >
+
+
@@ -19,6 +20,7 @@
+
diff --git a/scout_base/src/scout_base_node.cpp b/scout_base/src/scout_base_node.cpp
index 4b30af7..f59b337 100644
--- a/scout_base/src/scout_base_node.cpp
+++ b/scout_base/src/scout_base_node.cpp
@@ -27,6 +27,8 @@ int main(int argc, char **argv) {
private_node.param("simulated_robot", messenger.simulated_robot_,
false);
private_node.param("control_rate", messenger.sim_control_rate_, 50);
+ private_node.param("odom_topic_name", messenger.odom_topic_name_,
+ std::string("odom"));
if (!messenger.simulated_robot_) {
// connect to robot and setup ROS subscription
diff --git a/scout_base/src/scout_messenger.cpp b/scout_base/src/scout_messenger.cpp
index 426f5db..3e850ed 100644
--- a/scout_base/src/scout_messenger.cpp
+++ b/scout_base/src/scout_messenger.cpp
@@ -24,7 +24,7 @@ ScoutROSMessenger::ScoutROSMessenger(ScoutBase *scout, ros::NodeHandle *nh)
void ScoutROSMessenger::SetupSubscription() {
// odometry publisher
- odom_publisher_ = nh_->advertise(odom_frame_, 50);
+ odom_publisher_ = nh_->advertise(odom_topic_name_, 50);
status_publisher_ =
nh_->advertise("/scout_status", 10);
@@ -239,7 +239,7 @@ void ScoutROSMessenger::PublishOdometryToROS(double linear, double angular,
// publish odometry and tf messages
nav_msgs::Odometry odom_msg;
odom_msg.header.stamp = current_time_;
- odom_msg.header.frame_id = odom_frame_;
+ odom_msg.header.frame_id = "testes";
odom_msg.child_frame_id = base_frame_;
odom_msg.pose.pose.position.x = position_x_;