Struct ReactiveNav2DNode::MyReactiveInterface

Nested Relationships

This struct is a nested type of Class ReactiveNav2DNode.

Inheritance Relationships

Base Type

  • public mrpt::nav::CRobot2NavInterface

Struct Documentation

struct MyReactiveInterface : public mrpt::nav::CRobot2NavInterface

Public Functions

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

Get the current pose and speeds of the robot.

Parameters:
  • curPose – Current robot pose.

  • curV – Current linear speed, in meters per second.

  • curW – Current angular speed, in radians per second.

Returns:

false on any error.

bool changeSpeeds(const mrpt::kinematics::CVehicleVelCmd &vel_cmd) override

Change the instantaneous speeds of robot.

Parameters:
  • v – Linear speed, in meters per second.

  • w – Angular speed, in radians per second.

Returns:

false on any error.

bool stop(bool isEmergency) override
inline bool startWatchdog(float T_ms) override

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

Parameters:

T_ms – Period, in ms.

Returns:

false on any error.

inline bool stopWatchdog() override

Stop the watchdog timer.

Returns:

false on any error.

bool senseObstacles(mrpt::maps::CSimplePointsMap &obstacles, mrpt::system::TTimeStamp &timestamp) override

Return the current set of obstacle points.

Returns:

false on any error.

inline mrpt::kinematics::CVehicleVelCmd::Ptr getEmergencyStopCmd() override
inline mrpt::kinematics::CVehicleVelCmd::Ptr getStopCmd() override
void sendNavigationStartEvent() override

Callback: Start of navigation command

void sendNavigationEndEvent() override

Callback: End of navigation command (reach of single goal, or final waypoint of waypoint list)

void sendWaypointReachedEvent(int waypoint_index, bool reached_nSkipped) override

Callback: Reached an intermediary waypoint in waypoint list navigation. reached_nSkipped will be true if the waypoint was physically reached; false if it was actually “skipped”.

void sendNewWaypointTargetEvent(int waypoint_index) override

Callback: Heading towards a new intermediary/final waypoint in waypoint list navigation

void sendNavigationEndDueToErrorEvent() override

Callback: Error asking sensory data from robot or sending motor commands.

void sendWaySeemsBlockedEvent() override

Callback: No progression made towards target for a predefined period of time.

void sendApparentCollisionEvent() override

Callback: Apparent collision event (i.e. there is at least one obstacle point inside the robot shape)

void sendCannotGetCloserToBlockedTargetEvent() override

Callback: Target seems to be blocked by an obstacle.

Public Members

ReactiveNav2DNode &parent_