Handles the manipulation of robots (creation, deletion, move) More...
#include <handle_robot.h>
Public Member Functions | |
| bool | deleteRobot (const std::string &name) |
| Deletes a robot by frame_id. More... | |
| HandleRobot () | |
| Default constructor. More... | |
| bool | moveRobot (const std::string &name, const geometry_msgs::Pose2D newPose) |
| Re-places a robot by frame_id. More... | |
| stdr_msgs::RobotIndexedMsg | spawnNewRobot (const stdr_msgs::RobotMsg msg) |
| Spawns a new robot. More... | |
Private Attributes | |
| DeleteRobotClient | _deleteRobotClient |
| SpawnRobotClient | _spawnRobotClient |
| < Action client for spawning robots More... | |
Handles the manipulation of robots (creation, deletion, move)
Definition at line 50 of file handle_robot.h.
| stdr_robot::HandleRobot::HandleRobot | ( | ) |
| bool stdr_robot::HandleRobot::deleteRobot | ( | const std::string & | name | ) |
Deletes a robot by frame_id.
| name | [const std::string&] The robot frame_id to be deleted |
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.
| 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 |
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.
| msg | [const stdr_msgs::RobotMsg] The robot message from which the robot is created |
Definition at line 41 of file handle_robot.cpp.
|
private |
Definition at line 57 of file handle_robot.h.
|
private |
< Action client for spawning robots
Action client for deleting robots
Definition at line 55 of file handle_robot.h.