diff --git a/crosbot_explore/include/crosbot_explore/actionServer/basicClientCommands.hpp b/crosbot_explore/include/crosbot_explore/actionServer/basicClientCommands.hpp index 4cd55045125c9af1dee0d2c54589bead9fee4d68..a4ba77bccf6f33d77e42e474f3d3ff54da2cee19 100644 --- a/crosbot_explore/include/crosbot_explore/actionServer/basicClientCommands.hpp +++ b/crosbot_explore/include/crosbot_explore/actionServer/basicClientCommands.hpp @@ -8,13 +8,13 @@ #ifndef CROSBOT_EXPLORE_BASIC_CLIENT_COMMANDS_HPP_ #define CROSBOT_EXPLORE_BASIC_CLIENT_COMMANDS_HPP_ -#define DEFAULT_CONTROL_NAMESPACE "crosbot_explore" +#define CROSBOT_EXPLORE_DEFAULT_CONTROL_NAMESPACE "crosbot_explore" -#define COMMAND_GO_TO_ORIGIN "explore_command_go_to_origin" -#define COMMAND_GO_TO_POINT "explore_command_go_to_point" -#define COMMAND_GO_TO_POSE "explore_command_go_to_pose" -#define COMMAND_LEFTWALL_FOLLOW "explore_command_leftwall_follow" -#define COMMAND_RIGHTWALL_FOLLOW "explore_command_rightwall_follow" +#define CROSBOT_EXPLORE_COMMAND_GO_TO_ORIGIN "explore_command_go_to_origin" +#define CROSBOT_EXPLORE_COMMAND_GO_TO_POINT "explore_command_go_to_point" +#define CROSBOT_EXPLORE_COMMAND_GO_TO_POSE "explore_command_go_to_pose" +#define CROSBOT_EXPLORE_COMMAND_LEFTWALL_FOLLOW "explore_command_leftwall_follow" +#define CROSBOT_EXPLORE_COMMAND_RIGHTWALL_FOLLOW "explore_command_rightwall_follow" #endif /* CROSBOT_EXPLORE_BASIC_CLIENT_COMMANDS_HPP_ */ diff --git a/crosbot_explore/src/actionServer/basicClient.cpp b/crosbot_explore/src/actionServer/basicClient.cpp index 6e1038291cb96e9fa08b4f4fd23c1f65cbda3935..d24b1c9464fce850907bb537257b766dfa4b96d0 100644 --- a/crosbot_explore/src/actionServer/basicClient.cpp +++ b/crosbot_explore/src/actionServer/basicClient.cpp @@ -71,9 +71,9 @@ void BasicExplorerClient::startup() { // Use "local" namespace for config ros::NodeHandle nh("~"); - crosbotCommand = new crosbot::CrosbotCommand(DEFAULT_CONTROL_NAMESPACE, true, + crosbotCommand = new crosbot::CrosbotCommand(CROSBOT_EXPLORE_DEFAULT_CONTROL_NAMESPACE, true, new _CommandCallback(this)); - crosbotStatus = new crosbot::CrosbotStatus(DEFAULT_CONTROL_NAMESPACE); + crosbotStatus = new crosbot::CrosbotStatus(CROSBOT_EXPLORE_DEFAULT_CONTROL_NAMESPACE); aStarSrv = nh.serviceClient(aStarSrvName); pubPostrackReset = nh.advertise(postrackResetPub_name, 1); pubGraphSlamReset = nh.advertise(slamResetPub_name, 1); @@ -106,20 +106,20 @@ void BasicExplorerClient::callback_receivedCommand(const crosbot_msgs::ControlCo setExploreMode(crosbot_explore::ExploreMode::MODE_RESUME); } else if (command->command == crosbot_msgs::ControlCommand::CMD_STOP) { setExploreMode(crosbot_explore::ExploreMode::MODE_STOP); - } else if (command->command == COMMAND_LEFTWALL_FOLLOW) { + } else if (command->command == CROSBOT_EXPLORE_COMMAND_LEFTWALL_FOLLOW) { setExploreMode(crosbot_explore::ExploreMode::MODE_LEFT_WALL); - } else if (command->command == COMMAND_RIGHTWALL_FOLLOW) { + } else if (command->command == CROSBOT_EXPLORE_COMMAND_RIGHTWALL_FOLLOW) { setExploreMode(crosbot_explore::ExploreMode::MODE_RIGHT_WALL); - } else if (command->command == COMMAND_GO_TO_ORIGIN) { + } else if (command->command == CROSBOT_EXPLORE_COMMAND_GO_TO_ORIGIN) { setAStarPose(crosbot::Pose3D(), false); - } else if (command->command == COMMAND_GO_TO_POINT) { + } else if (command->command == CROSBOT_EXPLORE_COMMAND_GO_TO_POINT) { crosbot::Pose3D toPose = getCommandPoint(command); if (toPose.isFinite()) { setAStarPose(toPose, false); } else { STATUS_ERROR(crosbotStatus, "%s Go to Point failed - invalid point specified", LOG_START); } - } else if (command->command == COMMAND_GO_TO_POSE) { + } else if (command->command == CROSBOT_EXPLORE_COMMAND_GO_TO_POSE) { crosbot::Pose3D toPose = getCommandPose(command); if (toPose.isFinite()) { setAStarPose(toPose, true);