Public Member Functions | Public Attributes | List of all members
ReactiveNav2DNode::MyReactiveInterface Struct Reference
Inheritance diagram for ReactiveNav2DNode::MyReactiveInterface:
Inheritance graph
[legend]

Public Member Functions

bool changeSpeeds (const mrpt::kinematics::CVehicleVelCmd &vel_cmd) override
 
bool getCurrentPoseAndSpeeds (mrpt::math::TPose2D &curPose, mrpt::math::TTwist2D &curVel, mrpt::system::TTimeStamp &timestamp, mrpt::math::TPose2D &curOdometry, std::string &frame_id) override
 
mrpt::kinematics::CVehicleVelCmd::Ptr getEmergencyStopCmd () override
 
mrpt::kinematics::CVehicleVelCmd::Ptr getStopCmd () override
 
 MyReactiveInterface (ReactiveNav2DNode &parent)
 
virtual void sendNavigationEndDueToErrorEvent ()
 
virtual void sendNavigationEndEvent ()
 
virtual void sendNavigationStartEvent ()
 
virtual void sendWaySeemsBlockedEvent ()
 
bool senseObstacles (CSimplePointsMap &obstacles, mrpt::system::TTimeStamp &timestamp) override
 
virtual bool startWatchdog (float T_ms) override
 
bool stop (bool isEmergency) override
 
virtual bool stopWatchdog () override
 
- Public Member Functions inherited from mrpt::nav::CRobot2NavInterface
virtual bool changeSpeedsNOP ()
 
 CRobot2NavInterface ()
 
virtual mrpt::kinematics::CVehicleVelCmdPtr getAlignCmd (const double relative_heading_radians)
 
virtual double getNavigationTime ()
 
virtual void resetNavigationTimer ()
 
virtual void sendApparentCollisionEvent ()
 
virtual void sendApparentCollisionEvent ()
 
virtual void sendCannotGetCloserToBlockedTargetEvent (bool &do_abort_nav)
 
virtual void sendCannotGetCloserToBlockedTargetEvent (bool &do_abort_nav)
 
virtual void sendNewWaypointTargetEvent (int waypoint_index)
 
virtual void sendNewWaypointTargetEvent (int waypoint_index)
 
virtual void sendWaypointReachedEvent (int waypoint_index, bool reached_nSkipped)
 
virtual void sendWaypointReachedEvent (int waypoint_index, bool reached_nSkipped)
 
virtual ~CRobot2NavInterface ()
 

Public Attributes

ReactiveNav2DNodem_parent
 

Detailed Description

Definition at line 118 of file mrpt_reactivenav2d_node.cpp.

Constructor & Destructor Documentation

ReactiveNav2DNode::MyReactiveInterface::MyReactiveInterface ( ReactiveNav2DNode parent)
inline

Definition at line 124 of file mrpt_reactivenav2d_node.cpp.

Member Function Documentation

bool ReactiveNav2DNode::MyReactiveInterface::changeSpeeds ( const mrpt::kinematics::CVehicleVelCmd vel_cmd)
inlineoverridevirtual

Change the instantaneous speeds of robot.

Parameters
vLinear speed, in meters per second.
wAngular speed, in radians per second.
Returns
false on any error.

Implements mrpt::nav::CRobot2NavInterface.

Definition at line 187 of file mrpt_reactivenav2d_node.cpp.

bool ReactiveNav2DNode::MyReactiveInterface::getCurrentPoseAndSpeeds ( mrpt::math::TPose2D curPose,
mrpt::math::TTwist2D curVel,
mrpt::system::TTimeStamp timestamp,
mrpt::math::TPose2D curOdometry,
std::string frame_id 
)
inlineoverridevirtual

Get the current pose and speeds of the robot.

Parameters
curPoseCurrent robot pose.
curVCurrent linear speed, in meters per second.
curWCurrent angular speed, in radians per second.
Returns
false on any error.

Implements mrpt::nav::CRobot2NavInterface.

Definition at line 131 of file mrpt_reactivenav2d_node.cpp.

mrpt::kinematics::CVehicleVelCmd::Ptr ReactiveNav2DNode::MyReactiveInterface::getEmergencyStopCmd ( )
inlineoverridevirtual

Implements mrpt::nav::CRobot2NavInterface.

Definition at line 236 of file mrpt_reactivenav2d_node.cpp.

mrpt::kinematics::CVehicleVelCmd::Ptr ReactiveNav2DNode::MyReactiveInterface::getStopCmd ( )
inlineoverridevirtual

Implements mrpt::nav::CRobot2NavInterface.

Definition at line 240 of file mrpt_reactivenav2d_node.cpp.

virtual void ReactiveNav2DNode::MyReactiveInterface::sendNavigationEndDueToErrorEvent ( )
inlinevirtual

Reimplemented from mrpt::nav::CRobot2NavInterface.

Definition at line 251 of file mrpt_reactivenav2d_node.cpp.

virtual void ReactiveNav2DNode::MyReactiveInterface::sendNavigationEndEvent ( )
inlinevirtual

Reimplemented from mrpt::nav::CRobot2NavInterface.

Definition at line 250 of file mrpt_reactivenav2d_node.cpp.

virtual void ReactiveNav2DNode::MyReactiveInterface::sendNavigationStartEvent ( )
inlinevirtual

Reimplemented from mrpt::nav::CRobot2NavInterface.

Definition at line 249 of file mrpt_reactivenav2d_node.cpp.

virtual void ReactiveNav2DNode::MyReactiveInterface::sendWaySeemsBlockedEvent ( )
inlinevirtual

Reimplemented from mrpt::nav::CRobot2NavInterface.

Definition at line 252 of file mrpt_reactivenav2d_node.cpp.

bool ReactiveNav2DNode::MyReactiveInterface::senseObstacles ( CSimplePointsMap obstacles,
mrpt::system::TTimeStamp timestamp 
)
inlineoverridevirtual

Return the current set of obstacle points.

Returns
false on any error.

Implements mrpt::nav::CRobot2NavInterface.

Definition at line 224 of file mrpt_reactivenav2d_node.cpp.

virtual bool ReactiveNav2DNode::MyReactiveInterface::startWatchdog ( float  T_ms)
inlineoverridevirtual

Start the watchdog timer of the robot platform, if any.

Parameters
T_msPeriod, in ms.
Returns
false on any error.

Reimplemented from mrpt::nav::CRobot2NavInterface.

Definition at line 218 of file mrpt_reactivenav2d_node.cpp.

bool ReactiveNav2DNode::MyReactiveInterface::stop ( bool  isEmergency)
inlineoverridevirtual

Implements mrpt::nav::CRobot2NavInterface.

Definition at line 207 of file mrpt_reactivenav2d_node.cpp.

virtual bool ReactiveNav2DNode::MyReactiveInterface::stopWatchdog ( )
inlineoverridevirtual

Stop the watchdog timer.

Returns
false on any error.

Reimplemented from mrpt::nav::CRobot2NavInterface.

Definition at line 221 of file mrpt_reactivenav2d_node.cpp.

Member Data Documentation

ReactiveNav2DNode& ReactiveNav2DNode::MyReactiveInterface::m_parent

Definition at line 122 of file mrpt_reactivenav2d_node.cpp.


The documentation for this struct was generated from the following file:


mrpt_reactivenav2d
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Thu Mar 12 2020 03:22:13