The interactive world high level action server. More...
#include <HighLevelActions.h>
Public Member Functions | |
HighLevelActions () | |
Create a HighLevelActions and associated ROS information. | |
bool | okay () const |
A check for a valid HighLevelActions. | |
Static Public Attributes | |
static const int | AC_WAIT_TIME = 60 |
static const double | QUATERNION_90_ROTATE = 0.7071067811865476 |
static const double | SURFACE_Z_THRESH = 0.1 |
Private Member Functions | |
void | driveAndSearch (const interactive_world_msgs::DriveAndSearchGoalConstPtr &goal) |
Callback for the object search action server. | |
bool | driveHelper (const std::string &frame_id) |
Navigation helper. | |
void | driveToSurface (const interactive_world_msgs::DriveToSurfaceGoalConstPtr &goal) |
Callback for the drive to surface action server. | |
bool | findSurfaceCallback (interactive_world_msgs::FindSurface::Request &req, interactive_world_msgs::FindSurface::Response &resp) |
Callback for the find surface server. | |
bool | getSurfacesCallback (interactive_world_msgs::GetSurfaces::Request &req, interactive_world_msgs::GetSurfaces::Response &resp) |
void | recognizedObjectsCallback (const rail_manipulation_msgs::SegmentedObjectList &objects) |
Store the latest recognized objects. | |
tf2::Transform | tfFromPoseMessage (const geometry_msgs::Pose &pose) |
Create a new tf2 transform from a ROS message. | |
tf2::Transform | tfFromTFMessage (const geometry_msgs::Transform &tf) |
Create a new tf2 transform from a ROS message. | |
bool | transformToSurfaceFrame (interactive_world_msgs::TransformToSurfaceFrame::Request &req, interactive_world_msgs::TransformToSurfaceFrame::Response &resp) |
Private Attributes | |
ros::Duration | ac_wait_time_ |
bool | debug_ |
actionlib::SimpleActionServer < interactive_world_msgs::DriveAndSearchAction > | drive_and_search_as_ |
actionlib::SimpleActionServer < interactive_world_msgs::DriveToSurfaceAction > | drive_to_surface_as_ |
ros::ServiceServer | find_surface_srv_ |
std::string | fixed_frame_ |
ros::ServiceServer | get_surfaces_srv_ |
actionlib::SimpleActionClient < rail_manipulation_msgs::ArmAction > | home_arm_ac_ |
ros::ServiceClient | look_at_frame_srv_ |
actionlib::SimpleActionClient < move_base_msgs::MoveBaseAction > | nav_ac_ |
boost::mutex | nav_mutex_ |
ros::NodeHandle | node_ |
bool | okay_ |
ros::NodeHandle | private_node_ |
rail_manipulation_msgs::SegmentedObjectList | recognized_objects_ |
uint32_t | recognized_objects_counter_ |
boost::mutex | recognized_objects_mutex_ |
ros::Subscriber | recognized_objects_sub_ |
ros::ServiceClient | segment_srv_ |
std::map< std::string, geometry_msgs::TransformStamped > | static_tfs_ |
ros::ServiceServer | transform_to_surface_frame_srv_ |
World | world_ |
The interactive world high level action server.
The high level action server contains high level functionality for doing things such as driving to surfaces.
Definition at line 43 of file HighLevelActions.h.
Create a HighLevelActions and associated ROS information.
Creates a ROS node handle, subscribes to the relevant topics and servers, and creates interfaces for the different high level actions.
Definition at line 22 of file HighLevelActions.cpp.
void HighLevelActions::driveAndSearch | ( | const interactive_world_msgs::DriveAndSearchGoalConstPtr & | goal | ) | [private] |
Callback for the object search action server.
The search action will search for a given object at a given surface in the world.
goal | The goal object specifying the parameters. |
Definition at line 277 of file HighLevelActions.cpp.
bool HighLevelActions::driveHelper | ( | const std::string & | frame_id | ) | [private] |
Navigation helper.
Attempt to drive to the given frame.
frame_id | The frame ID to drive to. |
Definition at line 492 of file HighLevelActions.cpp.
void HighLevelActions::driveToSurface | ( | const interactive_world_msgs::DriveToSurfaceGoalConstPtr & | goal | ) | [private] |
Callback for the drive to surface action server.
The drive action will attempt to drive to a pre-defined naviagtion goal at a given surface.
goal | The goal object specifying the parameters. |
Definition at line 398 of file HighLevelActions.cpp.
bool HighLevelActions::findSurfaceCallback | ( | interactive_world_msgs::FindSurface::Request & | req, |
interactive_world_msgs::FindSurface::Response & | resp | ||
) | [private] |
Callback for the find surface server.
Searches for the surface in the world that the given point is on (within some threshold).
req | The request with the point to check. |
resp | The response with the surface name and frame (if any). |
Definition at line 198 of file HighLevelActions.cpp.
bool HighLevelActions::getSurfacesCallback | ( | interactive_world_msgs::GetSurfaces::Request & | req, |
interactive_world_msgs::GetSurfaces::Response & | resp | ||
) | [private] |
Definition at line 134 of file HighLevelActions.cpp.
bool HighLevelActions::okay | ( | ) | const |
A check for a valid HighLevelActions.
This function will return true if valid parameters were parsed from a YAML config file.
Definition at line 129 of file HighLevelActions.cpp.
void HighLevelActions::recognizedObjectsCallback | ( | const rail_manipulation_msgs::SegmentedObjectList & | objects | ) | [private] |
Store the latest recognized objects.
Stores the latest recognized objects from the segmentation topic.
objects | The latest recognized objects. |
Definition at line 522 of file HighLevelActions.cpp.
tf2::Transform HighLevelActions::tfFromPoseMessage | ( | const geometry_msgs::Pose & | pose | ) | [private] |
Create a new tf2 transform from a ROS message.
Creates and returns a new TF2 transform object from a ROS message.
pose | The ROS pose message to take values from. |
Definition at line 515 of file HighLevelActions.cpp.
tf2::Transform HighLevelActions::tfFromTFMessage | ( | const geometry_msgs::Transform & | tf | ) | [private] |
Create a new tf2 transform from a ROS message.
Creates and returns a new TF2 transform object from a ROS message.
tf | The ROS transform message to take values from. |
Definition at line 508 of file HighLevelActions.cpp.
bool HighLevelActions::transformToSurfaceFrame | ( | interactive_world_msgs::TransformToSurfaceFrame::Request & | req, |
interactive_world_msgs::TransformToSurfaceFrame::Response & | resp | ||
) | [private] |
Definition at line 149 of file HighLevelActions.cpp.
const int rail::interactive_world::HighLevelActions::AC_WAIT_TIME = 60 [static] |
The default wait time for action servers in seconds.
Definition at line 47 of file HighLevelActions.h.
The action client timeout.
Definition at line 171 of file HighLevelActions.h.
bool rail::interactive_world::HighLevelActions::debug_ [private] |
The okay check flags.
Definition at line 147 of file HighLevelActions.h.
actionlib::SimpleActionServer<interactive_world_msgs::DriveAndSearchAction> rail::interactive_world::HighLevelActions::drive_and_search_as_ [private] |
The object search action server.
Definition at line 157 of file HighLevelActions.h.
actionlib::SimpleActionServer<interactive_world_msgs::DriveToSurfaceAction> rail::interactive_world::HighLevelActions::drive_to_surface_as_ [private] |
The drive action server.
Definition at line 159 of file HighLevelActions.h.
The find surface server.
Definition at line 167 of file HighLevelActions.h.
std::string rail::interactive_world::HighLevelActions::fixed_frame_ [private] |
The fixed frame.
Definition at line 151 of file HighLevelActions.h.
Definition at line 167 of file HighLevelActions.h.
actionlib::SimpleActionClient<rail_manipulation_msgs::ArmAction> rail::interactive_world::HighLevelActions::home_arm_ac_ [private] |
The home arm action client.
Definition at line 163 of file HighLevelActions.h.
The camera and segmentation service clients.
Definition at line 165 of file HighLevelActions.h.
actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> rail::interactive_world::HighLevelActions::nav_ac_ [private] |
The navigation action client.
Definition at line 161 of file HighLevelActions.h.
boost::mutex rail::interactive_world::HighLevelActions::nav_mutex_ [private] |
The various mutexes used.
Definition at line 173 of file HighLevelActions.h.
The global and private ROS node handles.
Definition at line 149 of file HighLevelActions.h.
bool rail::interactive_world::HighLevelActions::okay_ [private] |
Definition at line 147 of file HighLevelActions.h.
Definition at line 149 of file HighLevelActions.h.
const double rail::interactive_world::HighLevelActions::QUATERNION_90_ROTATE = 0.7071067811865476 [static] |
Constant used for the W and Z components of a quaternion for a 90 degree rotation about the Z axis.
Definition at line 49 of file HighLevelActions.h.
rail_manipulation_msgs::SegmentedObjectList rail::interactive_world::HighLevelActions::recognized_objects_ [private] |
The latest recognized objects
Definition at line 175 of file HighLevelActions.h.
uint32_t rail::interactive_world::HighLevelActions::recognized_objects_counter_ [private] |
A counter for the number of recognized object messages that have come in.
Definition at line 177 of file HighLevelActions.h.
boost::mutex rail::interactive_world::HighLevelActions::recognized_objects_mutex_ [private] |
Definition at line 173 of file HighLevelActions.h.
The recognized objects topic.
Definition at line 169 of file HighLevelActions.h.
Definition at line 165 of file HighLevelActions.h.
std::map<std::string, geometry_msgs::TransformStamped> rail::interactive_world::HighLevelActions::static_tfs_ [private] |
Static transforms in the world.
Definition at line 155 of file HighLevelActions.h.
const double rail::interactive_world::HighLevelActions::SURFACE_Z_THRESH = 0.1 [static] |
Threshold on the Z axis for something being on a surface.
Definition at line 51 of file HighLevelActions.h.
ros::ServiceServer rail::interactive_world::HighLevelActions::transform_to_surface_frame_srv_ [private] |
Definition at line 167 of file HighLevelActions.h.
The world configuration.
Definition at line 153 of file HighLevelActions.h.