diff --git a/crosbot_explore/CMakeLists.txt b/crosbot_explore/CMakeLists.txt index 9aea873fe063bfce443ab0375ff1bf75899d99ff..f6d2c38fcadf5c0ce78727c5542dbbe38d52f07e 100644 --- a/crosbot_explore/CMakeLists.txt +++ b/crosbot_explore/CMakeLists.txt @@ -6,12 +6,17 @@ project(crosbot_explore) ## is used, also find other catkin packages find_package(catkin REQUIRED COMPONENTS roscpp - crosbot crosbot_map - geometry_msgs nav_msgs + geometry_msgs + nav_msgs dynamic_reconfigure message_generation - genmsg actionlib_msgs actionlib - ) + genmsg + actionlib_msgs + actionlib + crosbot + crosbot_map + crosbot_msgs +) ## System dependencies are found with CMake's conventions # find_package(Boost REQUIRED COMPONENTS system) @@ -77,8 +82,13 @@ catkin_package( INCLUDE_DIRS include LIBRARIES crosbot_explore CATKIN_DEPENDS - crosbot crosbot_map roscpp geometry_msgs nav_msgs + roscpp + geometry_msgs + nav_msgs actionlib_msgs + crosbot + crosbot_map + crosbot_msgs # DEPENDS system_lib ) diff --git a/crosbot_explore/include/crosbot_explore/actionServer/basicClient.hpp b/crosbot_explore/include/crosbot_explore/actionServer/basicClient.hpp index ef656569a4360f831e5cdff7e8d5d3debaa80338..4c927f70c8b801060661f20abbbe75f11f797f53 100644 --- a/crosbot_explore/include/crosbot_explore/actionServer/basicClient.hpp +++ b/crosbot_explore/include/crosbot_explore/actionServer/basicClient.hpp @@ -70,6 +70,12 @@ private: */ void setExploreMode(int mode); + /** + * Get command points + */ + crosbot::Pose3D getCommandPoint(const crosbot_msgs::ControlCommandPtr command); + crosbot::Pose3D getCommandPose(const crosbot_msgs::ControlCommandPtr command); + /** * Get A* path to origin and set path */ diff --git a/crosbot_explore/include/crosbot_explore/actionServer/basicClientCommands.hpp b/crosbot_explore/include/crosbot_explore/actionServer/basicClientCommands.hpp index 8407d5fcd071467f028c1a093d7fecca895e0bca..4cd55045125c9af1dee0d2c54589bead9fee4d68 100644 --- a/crosbot_explore/include/crosbot_explore/actionServer/basicClientCommands.hpp +++ b/crosbot_explore/include/crosbot_explore/actionServer/basicClientCommands.hpp @@ -11,6 +11,8 @@ #define 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" diff --git a/crosbot_explore/package.xml b/crosbot_explore/package.xml index e2227edc6835d8bdb119913be357e7e4d9acd630..0f3b8485b8060bfa96d79f25ffca2b4edf2f274b 100644 --- a/crosbot_explore/package.xml +++ b/crosbot_explore/package.xml @@ -35,6 +35,7 @@ actionlib_msgs crosbot crosbot_map + crosbot_msgs dynamic_reconfigure geometry_msgs nav_msgs diff --git a/crosbot_explore/src/actionServer/basicClient.cpp b/crosbot_explore/src/actionServer/basicClient.cpp index 4cfcea63a6c03122e757ae11d9264c9f9e0ce05a..6e1038291cb96e9fa08b4f4fd23c1f65cbda3935 100644 --- a/crosbot_explore/src/actionServer/basicClient.cpp +++ b/crosbot_explore/src/actionServer/basicClient.cpp @@ -112,6 +112,20 @@ void BasicExplorerClient::callback_receivedCommand(const crosbot_msgs::ControlCo setExploreMode(crosbot_explore::ExploreMode::MODE_RIGHT_WALL); } else if (command->command == COMMAND_GO_TO_ORIGIN) { setAStarPose(crosbot::Pose3D(), false); + } else if (command->command == 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) { + crosbot::Pose3D toPose = getCommandPose(command); + if (toPose.isFinite()) { + setAStarPose(toPose, true); + } else { + STATUS_ERROR(crosbotStatus, "%s Go to Pose failed - invalid point specified", LOG_START); + } } } @@ -137,6 +151,31 @@ void BasicExplorerClient::actionserver_feedback(const crosbot_explore::ExploreFe STATUS_INFO(crosbotStatus, "Explorer: %s (%s)", feedback->status.c_str(), searchStrategy.c_str()); } +crosbot::Pose3D BasicExplorerClient::getCommandPoint(const crosbot_msgs::ControlCommandPtr command) { + crosbot::Pose3D toPoint(INFINITY, INFINITY, INFINITY); + + if (command->args_doubles.size() >= 3) { + toPoint.position.x = command->args_doubles[0]; + toPoint.position.y = command->args_doubles[1]; + toPoint.position.z = command->args_doubles[2]; + } + + return toPoint; +} + +crosbot::Pose3D BasicExplorerClient::getCommandPose(const crosbot_msgs::ControlCommandPtr command) { + crosbot::Pose3D toPose = getCommandPoint(command); + + if (command->args_doubles.size() >= 7) { + toPose.orientation.x = command->args_doubles[3]; + toPose.orientation.y = command->args_doubles[4]; + toPose.orientation.z = command->args_doubles[5]; + toPose.orientation.w = command->args_doubles[6]; + } + + return toPose; +} + void BasicExplorerClient::setExploreMode(int mode) { // Ensure action server has started bool hasServer = actionClient->waitForServer(ros::Duration(DEFAULT_SERVER_WAIT));