Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Change internal map topic from "map" to "stdr_map" #164

Open
wants to merge 1 commit into
base: hydro-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion stdr_gui/include/stdr_gui/stdr_gui_controller.h
Original file line number Diff line number Diff line change
Expand Up @@ -232,7 +232,7 @@ namespace stdr_gui
void initializeCommunications(void);

/**
@brief Receives the occupancy grid map from stdr_server. Connects to "map" ROS topic
@brief Receives the occupancy grid map from stdr_server. Connects to "stdr_map" ROS topic
@param msg [const nav_msgs::OccupancyGrid&] The OGM message
@return void
**/
Expand Down
4 changes: 2 additions & 2 deletions stdr_gui/src/stdr_gui/stdr_gui_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ namespace stdr_gui
void CGuiController::initializeCommunications(void)
{
map_subscriber_ = n_.subscribe(
"map",
"stdr_map",
1,
&CGuiController::receiveMap,
this);
Expand Down Expand Up @@ -466,7 +466,7 @@ namespace stdr_gui
}

/**
@brief Receives the occupancy grid map from stdr_server. Connects to "map" \
@brief Receives the occupancy grid map from stdr_server. Connects to "stdr_map" \
ROS topic
@param msg [const nav_msgs::OccupancyGrid&] The OGM message
@return void
Expand Down
2 changes: 1 addition & 1 deletion stdr_robot/src/stdr_robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ namespace stdr_robot
_registerClientPtr->sendGoal(goal,
boost::bind(&Robot::initializeRobot, this, _1, _2));

_mapSubscriber = n.subscribe("map", 1, &Robot::mapCallback, this);
_mapSubscriber = n.subscribe("stdr_map", 1, &Robot::mapCallback, this);
_moveRobotService = n.advertiseService(
getName() + "/replace", &Robot::moveRobotCallback, this);

Expand Down
4 changes: 2 additions & 2 deletions stdr_server/src/map_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,11 +64,11 @@ namespace stdr_server {
&MapServer::publishTransform, this);

//!< Latched publisher for metadata
metadata_pub= n.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
metadata_pub= n.advertise<nav_msgs::MapMetaData>("stdr_map_metadata", 1, true);
metadata_pub.publish( meta_data_message_ );

//!< Latched publisher for data
map_pub = n.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
map_pub = n.advertise<nav_msgs::OccupancyGrid>("stdr_map", 1, true);
map_pub.publish( map_ );
}

Expand Down