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 Attributes | |
ReactiveNav2DNode & | m_parent |
Definition at line 118 of file mrpt_reactivenav2d_node.cpp.
ReactiveNav2DNode::MyReactiveInterface::MyReactiveInterface | ( | ReactiveNav2DNode & | parent | ) | [inline] |
Definition at line 124 of file mrpt_reactivenav2d_node.cpp.
bool ReactiveNav2DNode::MyReactiveInterface::changeSpeeds | ( | const mrpt::kinematics::CVehicleVelCmd & | vel_cmd | ) | [inline, override] |
Change the instantaneous speeds of robot.
v | Linear speed, in meters per second. |
w | Angular speed, in radians per second. |
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 | ||
) | [inline, override] |
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. |
Definition at line 131 of file mrpt_reactivenav2d_node.cpp.
mrpt::kinematics::CVehicleVelCmd::Ptr ReactiveNav2DNode::MyReactiveInterface::getEmergencyStopCmd | ( | ) | [inline, override] |
Definition at line 236 of file mrpt_reactivenav2d_node.cpp.
mrpt::kinematics::CVehicleVelCmd::Ptr ReactiveNav2DNode::MyReactiveInterface::getStopCmd | ( | ) | [inline, override] |
Definition at line 240 of file mrpt_reactivenav2d_node.cpp.
virtual void ReactiveNav2DNode::MyReactiveInterface::sendNavigationEndDueToErrorEvent | ( | ) | [inline, virtual] |
Definition at line 251 of file mrpt_reactivenav2d_node.cpp.
virtual void ReactiveNav2DNode::MyReactiveInterface::sendNavigationEndEvent | ( | ) | [inline, virtual] |
Definition at line 250 of file mrpt_reactivenav2d_node.cpp.
virtual void ReactiveNav2DNode::MyReactiveInterface::sendNavigationStartEvent | ( | ) | [inline, virtual] |
Definition at line 249 of file mrpt_reactivenav2d_node.cpp.
virtual void ReactiveNav2DNode::MyReactiveInterface::sendWaySeemsBlockedEvent | ( | ) | [inline, virtual] |
Definition at line 252 of file mrpt_reactivenav2d_node.cpp.
bool ReactiveNav2DNode::MyReactiveInterface::senseObstacles | ( | CSimplePointsMap & | obstacles, |
mrpt::system::TTimeStamp & | timestamp | ||
) | [inline, override] |
Return the current set of obstacle points.
Definition at line 224 of file mrpt_reactivenav2d_node.cpp.
virtual bool ReactiveNav2DNode::MyReactiveInterface::startWatchdog | ( | float | T_ms | ) | [inline, override, virtual] |
Start the watchdog timer of the robot platform, if any.
T_ms | Period, in ms. |
Definition at line 218 of file mrpt_reactivenav2d_node.cpp.
bool ReactiveNav2DNode::MyReactiveInterface::stop | ( | bool | isEmergency | ) | [inline, override] |
Definition at line 207 of file mrpt_reactivenav2d_node.cpp.
virtual bool ReactiveNav2DNode::MyReactiveInterface::stopWatchdog | ( | ) | [inline, override, virtual] |
Stop the watchdog timer.
Definition at line 221 of file mrpt_reactivenav2d_node.cpp.
Definition at line 122 of file mrpt_reactivenav2d_node.cpp.