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 ×tamp, 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 ×tamp) 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 | |
ReactiveNav2DNode & | m_parent |
Definition at line 118 of file mrpt_reactivenav2d_node.cpp.
|
inline |
Definition at line 124 of file mrpt_reactivenav2d_node.cpp.
|
inlineoverridevirtual |
Change the instantaneous speeds of robot.
v | Linear speed, in meters per second. |
w | Angular speed, in radians per second. |
Implements mrpt::nav::CRobot2NavInterface.
Definition at line 187 of file mrpt_reactivenav2d_node.cpp.
|
inlineoverridevirtual |
Get the current pose and speeds of the robot.
curPose | Current robot pose. |
curV | Current linear speed, in meters per second. |
curW | Current angular speed, in radians per second. |
Implements mrpt::nav::CRobot2NavInterface.
Definition at line 131 of file mrpt_reactivenav2d_node.cpp.
|
inlineoverridevirtual |
Implements mrpt::nav::CRobot2NavInterface.
Definition at line 236 of file mrpt_reactivenav2d_node.cpp.
|
inlineoverridevirtual |
Implements mrpt::nav::CRobot2NavInterface.
Definition at line 240 of file mrpt_reactivenav2d_node.cpp.
|
inlinevirtual |
Reimplemented from mrpt::nav::CRobot2NavInterface.
Definition at line 251 of file mrpt_reactivenav2d_node.cpp.
|
inlinevirtual |
Reimplemented from mrpt::nav::CRobot2NavInterface.
Definition at line 250 of file mrpt_reactivenav2d_node.cpp.
|
inlinevirtual |
Reimplemented from mrpt::nav::CRobot2NavInterface.
Definition at line 249 of file mrpt_reactivenav2d_node.cpp.
|
inlinevirtual |
Reimplemented from mrpt::nav::CRobot2NavInterface.
Definition at line 252 of file mrpt_reactivenav2d_node.cpp.
|
inlineoverridevirtual |
Return the current set of obstacle points.
Implements mrpt::nav::CRobot2NavInterface.
Definition at line 224 of file mrpt_reactivenav2d_node.cpp.
|
inlineoverridevirtual |
Start the watchdog timer of the robot platform, if any.
T_ms | Period, in ms. |
Reimplemented from mrpt::nav::CRobot2NavInterface.
Definition at line 218 of file mrpt_reactivenav2d_node.cpp.
|
inlineoverridevirtual |
Implements mrpt::nav::CRobot2NavInterface.
Definition at line 207 of file mrpt_reactivenav2d_node.cpp.
|
inlineoverridevirtual |
Stop the watchdog timer.
Reimplemented from mrpt::nav::CRobot2NavInterface.
Definition at line 221 of file mrpt_reactivenav2d_node.cpp.
ReactiveNav2DNode& ReactiveNav2DNode::MyReactiveInterface::m_parent |
Definition at line 122 of file mrpt_reactivenav2d_node.cpp.