Represents one robot in STDR. Inherts publicly from nodelet::Nodelet. More...
#include <stdr_robot.h>
Public Member Functions | |
void | initializeRobot (const actionlib::SimpleClientGoalState &state, const stdr_msgs::RegisterRobotResultConstPtr result) |
Initializes the robot after on registering it to server. | |
void | mapCallback (const nav_msgs::OccupancyGridConstPtr &msg) |
Callback for getting the occupancy grid map. | |
bool | moveRobotCallback (stdr_msgs::MoveRobot::Request &req, stdr_msgs::MoveRobot::Response &res) |
The callback of the re-place robot service. | |
void | onInit (void) |
Initializes the robot and gets the environment occupancy grid map. | |
Robot (void) | |
Default constructor. | |
~Robot (void) | |
Default destructor. | |
Private Member Functions | |
bool | checkUnknownOccupancy (const geometry_msgs::Pose2D &newPose) |
Checks the robot's reposition into unknown area. | |
bool | collisionExists (const geometry_msgs::Pose2D &newPose, const geometry_msgs::Pose2D &collisionPoint) |
Checks the robot collision -2b changed-. | |
bool | collisionExistsNoPath (const geometry_msgs::Pose2D &newPose) |
Checks the robot collision -2b changed-. | |
std::vector< std::pair< int, int > > | getPointsBetween (int x1, int y1, int x2, int y2) |
Robot's previous movement direction in X Axis. | |
void | publishTransforms (const ros::TimerEvent &) |
Publishes the tf transforms every with 10Hz. | |
Private Attributes | |
geometry_msgs::Pose2D | _currentPose |
Holds robots previous pose. | |
std::vector< std::pair< float, float > > | _footprint |
nav_msgs::OccupancyGrid | _map |
ROS tf transform broadcaster. | |
ros::Subscriber | _mapSubscriber |
< ROS subscriber for map | |
MotionControllerPtr | _motionControllerPtr |
Actionlib client for registering the robot. | |
ros::ServiceServer | _moveRobotService |
Container for robot sensors. | |
ros::Publisher | _odomPublisher |
Holds robots current pose. | |
bool | _previousMovementXAxis |
Robot's previous movement direction in Y Axis. | |
bool | _previousMovementYAxis |
geometry_msgs::Pose2D | _previousPose |
Pointer of a motion controller. | |
RegisterRobotClientPtr | _registerClientPtr |
The robot footprint in points (row * 10000 + col) | |
SensorPtrVector | _sensors |
The occupancy grid map. | |
tf::TransformBroadcaster | _tfBroadcaster |
Odometry Publisher. | |
ros::Timer | _tfTimer |
ROS service server to move robot. |
Represents one robot in STDR. Inherts publicly from nodelet::Nodelet.
Definition at line 58 of file stdr_robot.h.
Robot::Robot | ( | void | ) |
Robot::~Robot | ( | void | ) |
bool Robot::checkUnknownOccupancy | ( | const geometry_msgs::Pose2D & | newPose | ) | [private] |
Checks the robot's reposition into unknown area.
newPose | [const geometry_msgs::Pose2D] The pose for the robot to be moved to |
newPose | [const geometry_msgs::Pose2D] The pose for the robot to be moved to |
Definition at line 232 of file stdr_robot.cpp.
bool Robot::collisionExists | ( | const geometry_msgs::Pose2D & | newPose, |
const geometry_msgs::Pose2D & | previousPose | ||
) | [private] |
Checks the robot collision -2b changed-.
Definition at line 284 of file stdr_robot.cpp.
bool Robot::collisionExistsNoPath | ( | const geometry_msgs::Pose2D & | newPose | ) | [private] |
Checks the robot collision -2b changed-.
Definition at line 198 of file stdr_robot.cpp.
std::vector< std::pair< int, int > > Robot::getPointsBetween | ( | int | x1, |
int | y1, | ||
int | x2, | ||
int | y2 | ||
) | [private] |
Robot's previous movement direction in X Axis.
Returns the points between two points.
x1 | : The x coord of the first point |
y1 | : The y coord of the first point |
x2 | : The x coord of the second point |
y2 | : The y coord of the second point |
Definition at line 259 of file stdr_robot.cpp.
void Robot::initializeRobot | ( | const actionlib::SimpleClientGoalState & | state, |
const stdr_msgs::RegisterRobotResultConstPtr | result | ||
) |
Initializes the robot after on registering it to server.
state | [const actionlib::SimpleClientGoalState&] State of action |
result | [const stdr_msgs::RegisterRobotResultConstPtr] Action result of registering the robot |
Definition at line 74 of file stdr_robot.cpp.
void Robot::mapCallback | ( | const nav_msgs::OccupancyGridConstPtr & | msg | ) |
Callback for getting the occupancy grid map.
msg | [const nav_msgs::OccupancyGridConstPtr&] The occupancy grid map |
Definition at line 166 of file stdr_robot.cpp.
bool Robot::moveRobotCallback | ( | stdr_msgs::MoveRobot::Request & | req, |
stdr_msgs::MoveRobot::Response & | res | ||
) |
The callback of the re-place robot service.
req | [stdr_msgs::MoveRobot::Request&] The service request |
res | [stdr_msgs::MoveRobot::Response&] The service result |
Definition at line 177 of file stdr_robot.cpp.
void Robot::onInit | ( | void | ) | [virtual] |
Initializes the robot and gets the environment occupancy grid map.
Implements nodelet::Nodelet.
Definition at line 43 of file stdr_robot.cpp.
void Robot::publishTransforms | ( | const ros::TimerEvent & | ) | [private] |
Publishes the tf transforms every with 10Hz.
< Odometry
< Sensors tf
Definition at line 396 of file stdr_robot.cpp.
geometry_msgs::Pose2D stdr_robot::Robot::_currentPose [private] |
Holds robots previous pose.
Definition at line 158 of file stdr_robot.h.
std::vector<std::pair<float,float> > stdr_robot::Robot::_footprint [private] |
Definition at line 168 of file stdr_robot.h.
nav_msgs::OccupancyGrid stdr_robot::Robot::_map [private] |
ROS tf transform broadcaster.
Definition at line 149 of file stdr_robot.h.
< ROS subscriber for map
ROS timer to publish tf transforms (10Hz)
Definition at line 137 of file stdr_robot.h.
Actionlib client for registering the robot.
Definition at line 164 of file stdr_robot.h.
Container for robot sensors.
Definition at line 143 of file stdr_robot.h.
Holds robots current pose.
Definition at line 155 of file stdr_robot.h.
bool stdr_robot::Robot::_previousMovementXAxis [private] |
Robot's previous movement direction in Y Axis.
Definition at line 176 of file stdr_robot.h.
bool stdr_robot::Robot::_previousMovementYAxis [private] |
Definition at line 177 of file stdr_robot.h.
geometry_msgs::Pose2D stdr_robot::Robot::_previousPose [private] |
Pointer of a motion controller.
Definition at line 161 of file stdr_robot.h.
The robot footprint in points (row * 10000 + col)
Definition at line 167 of file stdr_robot.h.
SensorPtrVector stdr_robot::Robot::_sensors [private] |
The occupancy grid map.
Definition at line 146 of file stdr_robot.h.
Odometry Publisher.
Definition at line 152 of file stdr_robot.h.
ros::Timer stdr_robot::Robot::_tfTimer [private] |
ROS service server to move robot.
Definition at line 140 of file stdr_robot.h.