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

Represents one robot in STDR. Inherts publicly from nodelet::Nodelet. More...

#include <stdr_robot.h>

Inheritance diagram for stdr_robot::Robot:
Inheritance graph
[legend]

List of all members.

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.

Detailed Description

Represents one robot in STDR. Inherts publicly from nodelet::Nodelet.

Definition at line 59 of file stdr_robot.h.


Constructor & Destructor Documentation

Robot::Robot ( void  )

Default constructor.

Returns:
void

Definition at line 34 of file stdr_robot.cpp.

Robot::~Robot ( void  )

Default destructor.

Returns:
void

< Cleanup

Definition at line 470 of file stdr_robot.cpp.


Member Function Documentation

bool Robot::checkUnknownOccupancy ( const geometry_msgs::Pose2D &  newPose) [private]

Checks the robot's reposition into unknown area.

Parameters:
newPose[const geometry_msgs::Pose2D] The pose for the robot to be moved to
Returns:
True when position is in unknown area y
Parameters:
newPose[const geometry_msgs::Pose2D] The pose for the robot to be moved to
Returns:
True when position is in unknown area

Definition at line 249 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-.

Returns:
void
True on collision

Definition at line 301 of file stdr_robot.cpp.

bool Robot::collisionExistsNoPath ( const geometry_msgs::Pose2D &  newPose) [private]

Checks the robot collision -2b changed-.

Returns:
True on collision

Definition at line 215 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.

Parameters:
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
Returns:
The points inbetween

Definition at line 276 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.

Parameters:
state[const actionlib::SimpleClientGoalState&] State of action
result[const stdr_msgs::RegisterRobotResultConstPtr] Action result of registering the robot
Returns:
void

Definition at line 74 of file stdr_robot.cpp.

void Robot::mapCallback ( const nav_msgs::OccupancyGridConstPtr &  msg)

Callback for getting the occupancy grid map.

Parameters:
msg[const nav_msgs::OccupancyGridConstPtr&] The occupancy grid map
Returns:
void

Definition at line 183 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.

Parameters:
req[stdr_msgs::MoveRobot::Request&] The service request
res[stdr_msgs::MoveRobot::Response&] The service result
Returns:
bool

Definition at line 194 of file stdr_robot.cpp.

void Robot::onInit ( void  ) [virtual]

Initializes the robot and gets the environment occupancy grid map.

Returns:
void

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.

Returns:
void

< Odometry

< Sensors tf

Definition at line 413 of file stdr_robot.cpp.


Member Data Documentation

geometry_msgs::Pose2D stdr_robot::Robot::_currentPose [private]

Holds robots previous pose.

Definition at line 159 of file stdr_robot.h.

std::vector<std::pair<float,float> > stdr_robot::Robot::_footprint [private]

Definition at line 169 of file stdr_robot.h.

nav_msgs::OccupancyGrid stdr_robot::Robot::_map [private]

ROS tf transform broadcaster.

Definition at line 150 of file stdr_robot.h.

< ROS subscriber for map

ROS timer to publish tf transforms (10Hz)

Definition at line 138 of file stdr_robot.h.

Actionlib client for registering the robot.

Definition at line 165 of file stdr_robot.h.

Container for robot sensors.

Definition at line 144 of file stdr_robot.h.

Holds robots current pose.

Definition at line 156 of file stdr_robot.h.

Robot's previous movement direction in Y Axis.

Definition at line 177 of file stdr_robot.h.

Definition at line 178 of file stdr_robot.h.

geometry_msgs::Pose2D stdr_robot::Robot::_previousPose [private]

Pointer of a motion controller.

Definition at line 162 of file stdr_robot.h.

The robot footprint in points (row * 10000 + col)

Definition at line 168 of file stdr_robot.h.

The occupancy grid map.

Definition at line 147 of file stdr_robot.h.

Odometry Publisher.

Definition at line 153 of file stdr_robot.h.

ROS service server to move robot.

Definition at line 141 of file stdr_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 Thu Jun 6 2019 18:57:28