SMACC2
Public Member Functions | List of all members
sm_aws_warehouse_navigation::OrNavigation Class Reference

#include <or_navigation.hpp>

Inheritance diagram for sm_aws_warehouse_navigation::OrNavigation:
Inheritance graph
Collaboration diagram for sm_aws_warehouse_navigation::OrNavigation:
Collaboration graph

Public Member Functions

void onInitialize () override
 
void loadWaypointsFromYaml (WaypointNavigator *waypointsNavigator)
 
- Public Member Functions inherited from smacc2::Orthogonal< OrNavigation >
std::shared_ptr< ClientHandler< OrNavigation, TClient > > createClient (TArgs... args)
 
- Public Member Functions inherited from smacc2::ISmaccOrthogonal
void setStateMachine (ISmaccStateMachine *value)
 
ISmaccStateMachinegetStateMachine ()
 
void addClientBehavior (std::shared_ptr< smacc2::ISmaccClientBehavior > clientBehavior)
 
void runtimeConfigure ()
 
void onEntry ()
 
void onExit ()
 
virtual std::string getName () const
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage)
 
template<typename SmaccClientType >
bool requiresClient (SmaccClientType *&storage)
 
const std::vector< std::shared_ptr< smacc2::ISmaccClient > > & getClients ()
 
const std::vector< std::shared_ptr< smacc2::ISmaccClientBehavior > > & getClientBehaviors () const
 
template<typename T >
void setGlobalSMData (std::string name, T value)
 
template<typename T >
bool getGlobalSMData (std::string name, T &ret)
 
template<typename TClientBehavior >
TClientBehavior * getClientBehavior ()
 
rclcpp::Node::SharedPtr getNode ()
 
rclcpp::Logger getLogger ()
 

Additional Inherited Members

- Protected Member Functions inherited from smacc2::ISmaccOrthogonal
virtual void onInitialize ()
 
void initializeClients ()
 
template<typename TOrthogonal , typename TClient >
void assignClientToOrthogonal (TClient *client)
 
- Protected Attributes inherited from smacc2::ISmaccOrthogonal
std::vector< std::shared_ptr< smacc2::ISmaccClient > > clients_
 

Detailed Description

Definition at line 36 of file or_navigation.hpp.

Member Function Documentation

◆ loadWaypointsFromYaml()

void sm_aws_warehouse_navigation::OrNavigation::loadWaypointsFromYaml ( WaypointNavigator waypointsNavigator)
inline

Definition at line 67 of file or_navigation.hpp.

68 {
69 // if it is the first time and the waypoints navigator is not configured
70 std::string planfilepath;
71 getNode()->declare_parameter("waypoints_plan_2", planfilepath);
72 if (getNode()->get_parameter("waypoints_plan_2", planfilepath))
73 {
74 std::string package_share_directory =
75 ament_index_cpp::get_package_share_directory("sm_aws_warehouse_navigation");
76 boost::replace_all(planfilepath, "$(pkg_share)", package_share_directory);
77
78 waypointsNavigator->loadWayPointsFromFile2(planfilepath);
79 RCLCPP_INFO(getLogger(), "waypoints plan: %s", planfilepath.c_str());
80 }
81 else
82 {
83 RCLCPP_ERROR(getLogger(), "waypoints plan file not found: NONE");
84 exit(0);
85 }
86 }
rclcpp::Node::SharedPtr getNode()
Definition: orthogonal.cpp:47

References smacc2::ISmaccOrthogonal::getLogger(), smacc2::ISmaccOrthogonal::getNode(), and cl_nav2z::WaypointNavigator::loadWayPointsFromFile2().

Here is the call graph for this function:

◆ onInitialize()

void sm_aws_warehouse_navigation::OrNavigation::onInitialize ( )
inlineoverridevirtual

Reimplemented from smacc2::ISmaccOrthogonal.

Definition at line 39 of file or_navigation.hpp.

40 {
41 auto roslaunchClient =this->createClient<smacc2::client_bases::ClRosLaunch>("sm_aws_warehouse_navigation", "navigation_launch.py");
42
43 auto movebaseClient = this->createClient<cl_nav2z::ClNav2Z>();
44
45 // create pose component
46 movebaseClient->createComponent<cl_nav2z::Pose>(StandardReferenceFrames::Map);
47
48 // create planner switcher
49 movebaseClient->createComponent<cl_nav2z::PlannerSwitcher>();
50
51 // create goal checker switcher
52 movebaseClient->createComponent<cl_nav2z::GoalCheckerSwitcher>();
53
54 // create odom tracker
55 movebaseClient->createComponent<cl_nav2z::odom_tracker::OdomTracker>();
56
57 movebaseClient->createComponent<cl_nav2z::Amcl>();
58
59 // create waypoints navigator component
60 // auto waypointsNavigator = movebaseClient->createComponent<cl_nav2z::WaypointNavigator>();
61 // loadWaypointsFromYaml(waypointsNavigator);
62
63 // // change this to skip some points of the yaml file, default = 0
64 // waypointsNavigator->currentWaypoint_ = 0;
65 }

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