SMACC
|
#include <waypoints_navigator.h>
Public Member Functions | |
WaypointNavigator () | |
virtual void | onInitialize () override |
void | insertWaypoint (int index, geometry_msgs::Pose &newpose) |
void | removeWaypoint (int index) |
void | loadWayPointsFromFile (std::string filepath) |
void | setWaypoints (const std::vector< geometry_msgs::Pose > &waypoints) |
void | setWaypoints (const std::vector< Pose2D > &waypoints) |
void | sendNextGoal () |
const std::vector< geometry_msgs::Pose > & | getWaypoints () const |
long | getCurrentWaypointIndex () const |
template<typename TOrthogonal , typename TSourceObject > | |
void | onOrthogonalAllocation () |
Public Member Functions inherited from smacc::ISmaccComponent | |
ISmaccComponent () | |
virtual | ~ISmaccComponent () |
virtual std::string | getName () const |
Public Attributes | |
WaypointEventDispatcher | waypointsEventDispatcher |
ClMoveBaseZ * | client_ |
int | currentWaypoint_ |
Private Member Functions | |
void | onGoalReached (ClMoveBaseZ::ResultConstPtr &res) |
Private Attributes | |
std::vector< geometry_msgs::Pose > | waypoints_ |
boost::signals2::connection | succeddedConnection_ |
Additional Inherited Members | |
Protected Member Functions inherited from smacc::ISmaccComponent | |
virtual void | initialize (ISmaccClient *owner) |
void | setStateMachine (ISmaccStateMachine *stateMachine) |
template<typename EventType > | |
void | postEvent (const EventType &ev) |
template<typename EventType > | |
void | postEvent () |
template<typename TOrthogonal , typename TSourceObject > | |
void | onOrthogonalAllocation () |
template<typename TComponent > | |
void | requiresComponent (TComponent *&requiredComponentStorage) |
template<typename TClient > | |
void | requiresClient (TClient *&requiredClientStorage) |
virtual void | onInitialize () |
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs> | |
SmaccComponentType * | createSiblingComponent (TArgs... targs) |
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs> | |
SmaccComponentType * | createSiblingNamedComponent (std::string name, TArgs... targs) |
Protected Attributes inherited from smacc::ISmaccComponent | |
ISmaccStateMachine * | stateMachine_ |
ISmaccClient * | owner_ |
Definition at line 32 of file waypoints_navigator.h.
cl_move_base_z::WaypointNavigator::WaypointNavigator | ( | ) |
Definition at line 14 of file waypoints_navigator.cpp.
long cl_move_base_z::WaypointNavigator::getCurrentWaypointIndex | ( | ) | const |
Definition at line 110 of file waypoints_navigator.cpp.
References currentWaypoint_.
const std::vector< geometry_msgs::Pose > & cl_move_base_z::WaypointNavigator::getWaypoints | ( | ) | const |
Definition at line 105 of file waypoints_navigator.cpp.
References waypoints_.
void cl_move_base_z::WaypointNavigator::insertWaypoint | ( | int | index, |
geometry_msgs::Pose & | newpose | ||
) |
void cl_move_base_z::WaypointNavigator::loadWayPointsFromFile | ( | std::string | filepath | ) |
Definition at line 116 of file waypoints_navigator.cpp.
References waypoints_.
|
private |
Definition at line 25 of file waypoints_navigator.cpp.
References currentWaypoint_, cl_move_base_z::WaypointEventDispatcher::postWaypointEvent(), succeddedConnection_, and waypointsEventDispatcher.
Referenced by sendNextGoal().
|
overridevirtual |
Reimplemented from smacc::ISmaccComponent.
Definition at line 20 of file waypoints_navigator.cpp.
References client_, and smacc::ISmaccComponent::owner_.
|
inline |
Definition at line 60 of file waypoints_navigator.h.
References client_, cl_move_base_z::WaypointEventDispatcher::initialize(), and waypointsEventDispatcher.
void cl_move_base_z::WaypointNavigator::removeWaypoint | ( | int | index | ) |
void cl_move_base_z::WaypointNavigator::sendNextGoal | ( | ) |
Definition at line 32 of file waypoints_navigator.cpp.
References client_, currentWaypoint_, smacc::ISmaccClient::getComponent(), onGoalReached(), smacc::client_bases::SmaccActionClientBase< ActionType >::onSucceeded(), cl_move_base_z::odom_tracker::RECORD_PATH, smacc::client_bases::SmaccActionClientBase< ActionType >::sendGoal(), cl_move_base_z::PlannerSwitcher::setDefaultPlanners(), succeddedConnection_, and waypoints_.
Referenced by cl_move_base_z::CbNavigateNextWaypoint::onEntry().
void cl_move_base_z::WaypointNavigator::setWaypoints | ( | const std::vector< geometry_msgs::Pose > & | waypoints | ) |
Definition at line 77 of file waypoints_navigator.cpp.
References waypoints_.
void cl_move_base_z::WaypointNavigator::setWaypoints | ( | const std::vector< Pose2D > & | waypoints | ) |
Definition at line 82 of file waypoints_navigator.cpp.
References waypoints_.
ClMoveBaseZ* cl_move_base_z::WaypointNavigator::client_ |
Definition at line 37 of file waypoints_navigator.h.
Referenced by onInitialize(), onOrthogonalAllocation(), and sendNextGoal().
int cl_move_base_z::WaypointNavigator::currentWaypoint_ |
Definition at line 65 of file waypoints_navigator.h.
Referenced by getCurrentWaypointIndex(), onGoalReached(), and sendNextGoal().
|
private |
Definition at line 72 of file waypoints_navigator.h.
Referenced by onGoalReached(), and sendNextGoal().
|
private |
Definition at line 70 of file waypoints_navigator.h.
Referenced by getWaypoints(), insertWaypoint(), loadWayPointsFromFile(), removeWaypoint(), sendNextGoal(), and setWaypoints().
WaypointEventDispatcher cl_move_base_z::WaypointNavigator::waypointsEventDispatcher |
Definition at line 35 of file waypoints_navigator.h.
Referenced by onGoalReached(), and onOrthogonalAllocation().