Public Member Functions | Private Attributes
stdr_robot::HandleRobot Class Reference

Handles the manipulation of robots (creation, deletion, move) More...

#include <handle_robot.h>

List of all members.

Public Member Functions

bool deleteRobot (const std::string &name)
 Deletes a robot by frame_id.
 HandleRobot ()
 Default constructor.
bool moveRobot (const std::string &name, const geometry_msgs::Pose2D newPose)
 Re-places a robot by frame_id.
stdr_msgs::RobotIndexedMsg spawnNewRobot (const stdr_msgs::RobotMsg msg)
 Spawns a new robot.

Private Attributes

DeleteRobotClient _deleteRobotClient
SpawnRobotClient _spawnRobotClient
 < Action client for spawning robots

Detailed Description

Handles the manipulation of robots (creation, deletion, move)

Definition at line 50 of file handle_robot.h.


Constructor & Destructor Documentation

Default constructor.

Returns:
void

Definition at line 30 of file handle_robot.cpp.


Member Function Documentation

bool stdr_robot::HandleRobot::deleteRobot ( const std::string &  name)

Deletes a robot by frame_id.

Parameters:
name[const std::string&] The robot frame_id to be deleted
Returns:
bool : True if deletion was successful

Definition at line 79 of file handle_robot.cpp.

bool stdr_robot::HandleRobot::moveRobot ( const std::string &  name,
const geometry_msgs::Pose2D  newPose 
)

Re-places a robot by frame_id.

Parameters:
name[const std::string&] The robot frame_id to be moved
newPose[const geometry_msgs::Pose2D] The pose for the robot to be moved to
Returns:
bool : True if move was successful

Definition at line 107 of file handle_robot.cpp.

stdr_msgs::RobotIndexedMsg stdr_robot::HandleRobot::spawnNewRobot ( const stdr_msgs::RobotMsg  msg)

Spawns a new robot.

Parameters:
msg[const stdr_msgs::RobotMsg] The robot message from which the robot is created
Returns:
stdr_msgs::RobotIndexedMsg : The robot message with the proper frame_id

Definition at line 41 of file handle_robot.cpp.


Member Data Documentation

Definition at line 57 of file handle_robot.h.

< Action client for spawning robots

Action client for deleting robots

Definition at line 56 of file handle_robot.h.


The documentation for this class was generated from the following files:


stdr_robot
Author(s): Manos Tsardoulias, Chris Zalidis, Aris Thallas
autogenerated on Wed Sep 2 2015 03:36:25