SMACC2
Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
cl_nav2z::WaypointNavigator Class Reference

#include <waypoints_navigator.hpp>

Inheritance diagram for cl_nav2z::WaypointNavigator:
Inheritance graph
Collaboration diagram for cl_nav2z::WaypointNavigator:
Collaboration graph

Public Member Functions

 WaypointNavigator ()
 
void onInitialize () override
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
void loadWayPointsFromFile (std::string filepath)
 
void loadWayPointsFromFile2 (std::string filepath)
 
void setWaypoints (const std::vector< geometry_msgs::msg::Pose > &waypoints)
 
void setWaypoints (const std::vector< Pose2D > &waypoints)
 
void sendNextGoal ()
 
void stopWaitingResult ()
 
const std::vector< geometry_msgs::msg::Pose > & getWaypoints () const
 
long getCurrentWaypointIndex () const
 
void rewind (int count)
 
- Public Member Functions inherited from smacc2::ISmaccComponent
 ISmaccComponent ()
 
virtual ~ISmaccComponent ()
 
virtual std::string getName () const
 

Public Attributes

WaypointEventDispatcher waypointsEventDispatcher
 
ClNav2Zclient_
 
long currentWaypoint_
 
smacc2::SmaccSignal< void()> onNavigationRequestSucceded
 
smacc2::SmaccSignal< void()> onNavigationRequestAborted
 
smacc2::SmaccSignal< void()> onNavigationRequestCancelled
 

Private Member Functions

void insertWaypoint (int index, geometry_msgs::msg::Pose &newpose)
 
void removeWaypoint (int index)
 
void onGoalReached (ClNav2Z::WrappedResult &res)
 
void onGoalCancelled (ClNav2Z::WrappedResult &)
 
void onGoalAborted (ClNav2Z::WrappedResult &)
 

Private Attributes

std::vector< geometry_msgs::msg::Pose > waypoints_
 
std::vector< std::string > waypointsNames_
 
boost::signals2::connection succeddedNav2ZClientConnection_
 
boost::signals2::connection abortedNav2ZClientConnection_
 
boost::signals2::connection cancelledNav2ZClientConnection_
 

Additional Inherited Members

- Protected Member Functions inherited from smacc2::ISmaccComponent
virtual void onInitialize ()
 
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)
 
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)
 
rclcpp::Node::SharedPtr getNode ()
 
rclcpp::Logger getLogger ()
 
ISmaccStateMachinegetStateMachine ()
 
- Protected Attributes inherited from smacc2::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

Definition at line 49 of file waypoints_navigator.hpp.

Constructor & Destructor Documentation

◆ WaypointNavigator()

cl_nav2z::WaypointNavigator::WaypointNavigator ( )

Definition at line 37 of file waypoints_navigator.cpp.

std::vector< geometry_msgs::msg::Pose > waypoints_

Member Function Documentation

◆ getCurrentWaypointIndex()

long cl_nav2z::WaypointNavigator::getCurrentWaypointIndex ( ) const

Definition at line 189 of file waypoints_navigator.cpp.

189{ return currentWaypoint_; }

References currentWaypoint_.

Referenced by cl_nav2z::CbNavigateNextWaypoint::onEntry().

Here is the caller graph for this function:

◆ getWaypoints()

const std::vector< geometry_msgs::msg::Pose > & cl_nav2z::WaypointNavigator::getWaypoints ( ) const

Definition at line 184 of file waypoints_navigator.cpp.

185{
186 return waypoints_;
187}

References waypoints_.

◆ insertWaypoint()

void cl_nav2z::WaypointNavigator::insertWaypoint ( int  index,
geometry_msgs::msg::Pose &  newpose 
)
private

Definition at line 143 of file waypoints_navigator.cpp.

144{
145 if (index >= 0 && index <= (int)waypoints_.size())
146 {
147 waypoints_.insert(waypoints_.begin(), index, newpose);
148 }
149}

References waypoints_.

◆ loadWayPointsFromFile()

void cl_nav2z::WaypointNavigator::loadWayPointsFromFile ( std::string  filepath)

Definition at line 192 of file waypoints_navigator.cpp.

193{
194 RCLCPP_INFO_STREAM(getLogger(), "[WaypointNavigator] Loading file:" << filepath);
195 this->waypoints_.clear();
196 std::ifstream ifs(filepath.c_str(), std::ifstream::in);
197 if (ifs.good() == false)
198 {
199 throw std::string("Waypoints file not found");
200 }
201
202 try
203 {
204#ifdef HAVE_NEW_YAMLCPP
205 YAML::Node node = YAML::Load(ifs);
206#else
207 YAML::Parser parser(ifs);
208 parser.GetNextDocument(node);
209#endif
210
211#ifdef HAVE_NEW_YAMLCPP
212 const YAML::Node & wp_node_tmp = node["waypoints"];
213 const YAML::Node * wp_node = wp_node_tmp ? &wp_node_tmp : NULL;
214#else
215 const YAML::Node * wp_node = node.FindValue("waypoints");
216#endif
217
218 if (wp_node != NULL)
219 {
220 for (unsigned int i = 0; i < wp_node->size(); ++i)
221 {
222 // Parse waypoint entries on YAML
223 geometry_msgs::msg::Pose wp;
224
225 try
226 {
227 // (*wp_node)[i]["name"] >> wp.name;
228 // (*wp_node)[i]["frame_id"] >> wp.header.frame_id;
229 wp.position.x = (*wp_node)[i]["position"]["x"].as<double>();
230 wp.position.y = (*wp_node)[i]["position"]["y"].as<double>();
231 wp.position.z = (*wp_node)[i]["position"]["z"].as<double>();
232 wp.orientation.x = (*wp_node)[i]["orientation"]["x"].as<double>();
233 wp.orientation.y = (*wp_node)[i]["orientation"]["y"].as<double>();
234 wp.orientation.z = (*wp_node)[i]["orientation"]["z"].as<double>();
235 wp.orientation.w = (*wp_node)[i]["orientation"]["w"].as<double>();
236
237 this->waypoints_.push_back(wp);
238 }
239 catch (...)
240 {
241 RCLCPP_ERROR(getLogger(), "parsing waypoint file, syntax error in point %d", i);
242 }
243 }
244 RCLCPP_INFO_STREAM(getLogger(), "Parsed " << this->waypoints_.size() << " waypoints.");
245 }
246 else
247 {
248 RCLCPP_WARN_STREAM(getLogger(), "Couldn't find any waypoints in the provided yaml file.");
249 }
250 }
251 catch (const YAML::ParserException & ex)
252 {
253 RCLCPP_ERROR_STREAM(
254 getLogger(), "Error loading the Waypoints YAML file. Incorrect syntax: " << ex.what());
255 }
256}
rclcpp::Logger getLogger()

References smacc2::ISmaccComponent::getLogger(), generate_debs::parser, and waypoints_.

Referenced by sm_dance_bot::OrNavigation::loadWaypointsFromYaml(), sm_dance_bot_strikes_back::OrNavigation::loadWaypointsFromYaml(), and sm_husky_barrel_search_1::OrNavigation::loadWaypointsFromYaml().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ loadWayPointsFromFile2()

void cl_nav2z::WaypointNavigator::loadWayPointsFromFile2 ( std::string  filepath)

Definition at line 258 of file waypoints_navigator.cpp.

259{
260 RCLCPP_INFO_STREAM(getLogger(), "[WaypointNavigator] Loading file:" << filepath);
261 this->waypoints_.clear();
262 std::ifstream ifs(filepath.c_str(), std::ifstream::in);
263 if (ifs.good() == false)
264 {
265 throw std::string("Waypoints file not found");
266 }
267
268 try
269 {
270#ifdef HAVE_NEW_YAMLCPP
271 YAML::Node node = YAML::Load(ifs);
272#else
273 YAML::Parser parser(ifs);
274 parser.GetNextDocument(node);
275#endif
276
277#ifdef HAVE_NEW_YAMLCPP
278 const YAML::Node & wp_node_tmp = node["waypoints"];
279 const YAML::Node * wp_node = wp_node_tmp ? &wp_node_tmp : NULL;
280#else
281 const YAML::Node * wp_node = node.FindValue("waypoints");
282#endif
283
284 if (wp_node != NULL)
285 {
286 for (unsigned int i = 0; i < wp_node->size(); ++i)
287 {
288 // Parse waypoint entries on YAML
289 geometry_msgs::msg::Pose wp;
290
291 try
292 {
293 // (*wp_node)[i]["name"] >> wp.name;
294 // (*wp_node)[i]["frame_id"] >> wp.header.frame_id;
295 wp.position.x = (*wp_node)[i]["x"].as<double>();
296 wp.position.y = (*wp_node)[i]["y"].as<double>();
297 auto name = (*wp_node)[i]["name"].as<std::string>();
298
299 this->waypoints_.push_back(wp);
300 this->waypointsNames_.push_back(name);
301 }
302 catch (...)
303 {
304 RCLCPP_ERROR(getLogger(), "parsing waypoint file, syntax error in point %d", i);
305 }
306 }
307 RCLCPP_INFO_STREAM(getLogger(), "Parsed " << this->waypoints_.size() << " waypoints.");
308 }
309 else
310 {
311 RCLCPP_WARN_STREAM(getLogger(), "Couldn't find any waypoints in the provided yaml file.");
312 }
313 }
314 catch (const YAML::ParserException & ex)
315 {
316 RCLCPP_ERROR_STREAM(
317 getLogger(), "Error loading the Waypoints YAML file. Incorrect syntax: " << ex.what());
318 }
319}
std::vector< std::string > waypointsNames_

References smacc2::ISmaccComponent::getLogger(), generate_debs::parser, waypoints_, and waypointsNames_.

Referenced by sm_aws_warehouse_navigation::OrNavigation::loadWaypointsFromYaml().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onGoalAborted()

void cl_nav2z::WaypointNavigator::onGoalAborted ( ClNav2Z::WrappedResult )
private

Definition at line 48 of file waypoints_navigator.cpp.

49{
51
53}
smacc2::SmaccSignal< void()> onNavigationRequestAborted

References onNavigationRequestAborted, and stopWaitingResult().

Referenced by sendNextGoal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onGoalCancelled()

void cl_nav2z::WaypointNavigator::onGoalCancelled ( ClNav2Z::WrappedResult )
private

Definition at line 41 of file waypoints_navigator.cpp.

42{
44
46}
smacc2::SmaccSignal< void()> onNavigationRequestCancelled

References onNavigationRequestCancelled, and stopWaitingResult().

Referenced by sendNextGoal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onGoalReached()

void cl_nav2z::WaypointNavigator::onGoalReached ( ClNav2Z::WrappedResult res)
private

Definition at line 55 of file waypoints_navigator.cpp.

56{
59 RCLCPP_WARN(
60 getLogger(), "[WaypointNavigator] Goal result received, incrementing waypoint index: %ld",
63
65}
WaypointEventDispatcher waypointsEventDispatcher
smacc2::SmaccSignal< void()> onNavigationRequestSucceded

References currentWaypoint_, smacc2::ISmaccComponent::getLogger(), onNavigationRequestSucceded, cl_nav2z::WaypointEventDispatcher::postWaypointEvent(), stopWaitingResult(), and waypointsEventDispatcher.

Referenced by sendNextGoal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onInitialize()

void cl_nav2z::WaypointNavigator::onInitialize ( )
overridevirtual

Reimplemented from smacc2::ISmaccComponent.

Definition at line 39 of file waypoints_navigator.cpp.

39{ client_ = dynamic_cast<ClNav2Z *>(owner_); }
ISmaccClient * owner_
Definition: component.hpp:77

References client_, and smacc2::ISmaccComponent::owner_.

◆ onOrthogonalAllocation()

template<typename TOrthogonal , typename TSourceObject >
void cl_nav2z::WaypointNavigator::onOrthogonalAllocation ( )
inline

Definition at line 61 of file waypoints_navigator.hpp.

62 {
63 waypointsEventDispatcher.initialize<TSourceObject, TOrthogonal>(client_);
64 }

References client_, cl_nav2z::WaypointEventDispatcher::initialize(), and waypointsEventDispatcher.

Here is the call graph for this function:

◆ removeWaypoint()

void cl_nav2z::WaypointNavigator::removeWaypoint ( int  index)
private

Definition at line 176 of file waypoints_navigator.cpp.

177{
178 if (index >= 0 && index < (int)waypoints_.size())
179 {
180 waypoints_.erase(waypoints_.begin() + index);
181 }
182}

References waypoints_.

◆ rewind()

void cl_nav2z::WaypointNavigator::rewind ( int  count)

Definition at line 67 of file waypoints_navigator.cpp.

68{
71}

References currentWaypoint_.

◆ sendNextGoal()

void cl_nav2z::WaypointNavigator::sendNextGoal ( )

Definition at line 83 of file waypoints_navigator.cpp.

84{
85 if (currentWaypoint_ >= 0 && currentWaypoint_ < (int)waypoints_.size())
86 {
87 auto & next = waypoints_[currentWaypoint_];
88
89 ClNav2Z::Goal goal;
91 auto pose = p->toPoseMsg();
92
93 // configuring goal
94 goal.pose.header.frame_id = p->getReferenceFrame();
95 goal.pose.header.stamp = getNode()->now();
96 goal.pose.pose = next;
97
98 RCLCPP_WARN(getLogger(), "[WaypointsNavigator] Configuring default planners");
99 auto plannerSwitcher = client_->getComponent<PlannerSwitcher>();
100 plannerSwitcher->setDefaultPlanners();
101
102 RCLCPP_WARN(getLogger(), "[WaypointsNavigator] Configuring default goal planner");
103 auto goalCheckerSwitcher = client_->getComponent<GoalCheckerSwitcher>();
104 goalCheckerSwitcher->setGoalCheckerId("goal_checker");
105
106 // publish stuff
107 // rclcpp::sleep_for(5s);
108
109 RCLCPP_INFO(getLogger(), "[WaypointsNavigator] Getting odom tracker");
111 if (odomTracker != nullptr)
112 {
113 RCLCPP_INFO(getLogger(), "[WaypointsNavigator] Storing path in odom tracker");
114
115 auto pathname =
116 this->owner_->getStateMachine()->getCurrentState()->getName() + " - " + getName();
117 odomTracker->pushPath(pathname);
118 odomTracker->setStartPoint(pose);
119 odomTracker->setWorkingMode(cl_nav2z::odom_tracker::WorkingMode::RECORD_PATH);
120 }
121
122 // SEND GOAL
123 if (!succeddedNav2ZClientConnection_.connected())
124 {
131 }
132
133 client_->sendGoal(goal);
134 }
135 else
136 {
137 RCLCPP_WARN(
138 getLogger(),
139 "[WaypointsNavigator] All waypoints were consumed. There is no more waypoints available.");
140 }
141}
geometry_msgs::msg::Pose toPoseMsg()
Definition: cp_pose.hpp:58
boost::signals2::connection cancelledNav2ZClientConnection_
void onGoalCancelled(ClNav2Z::WrappedResult &)
boost::signals2::connection abortedNav2ZClientConnection_
boost::signals2::connection succeddedNav2ZClientConnection_
void onGoalAborted(ClNav2Z::WrappedResult &)
void onGoalReached(ClNav2Z::WrappedResult &res)
ISmaccStateMachine * getStateMachine()
TComponent * getComponent()
virtual std::string getName() const
rclcpp::Node::SharedPtr getNode()
virtual std::string getName()=0
boost::signals2::connection onAborted(void(T::*callback)(WrappedResult &), T *object)
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal)
boost::signals2::connection onSucceeded(void(T::*callback)(WrappedResult &), T *object)
boost::signals2::connection onCancelled(void(T::*callback)(WrappedResult &), T *object)

References abortedNav2ZClientConnection_, cancelledNav2ZClientConnection_, client_, currentWaypoint_, smacc2::ISmaccClient::getComponent(), smacc2::ISmaccStateMachine::getCurrentState(), smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), smacc2::ISmaccState::getName(), smacc2::ISmaccComponent::getNode(), smacc2::ISmaccClient::getStateMachine(), smacc2::client_bases::SmaccActionClientBase< ActionType >::onAborted(), smacc2::client_bases::SmaccActionClientBase< ActionType >::onCancelled(), onGoalAborted(), onGoalCancelled(), onGoalReached(), smacc2::client_bases::SmaccActionClientBase< ActionType >::onSucceeded(), smacc2::ISmaccComponent::owner_, cl_nav2z::odom_tracker::RECORD_PATH, smacc2::client_bases::SmaccActionClientBase< ActionType >::sendGoal(), cl_nav2z::PlannerSwitcher::setDefaultPlanners(), cl_nav2z::GoalCheckerSwitcher::setGoalCheckerId(), succeddedNav2ZClientConnection_, cl_nav2z::Pose::toPoseMsg(), and waypoints_.

Referenced by cl_nav2z::CbNavigateNextWaypoint::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setWaypoints() [1/2]

void cl_nav2z::WaypointNavigator::setWaypoints ( const std::vector< geometry_msgs::msg::Pose > &  waypoints)

Definition at line 151 of file waypoints_navigator.cpp.

152{
153 this->waypoints_ = waypoints;
154}

References waypoints_.

◆ setWaypoints() [2/2]

void cl_nav2z::WaypointNavigator::setWaypoints ( const std::vector< Pose2D > &  waypoints)

Definition at line 156 of file waypoints_navigator.cpp.

157{
158 waypoints_.clear();
159 waypointsNames_.clear();
160 int i = 0;
161 for (auto & p : waypoints)
162 {
163 geometry_msgs::msg::Pose pose;
164 pose.position.x = p.x_;
165 pose.position.y = p.y_;
166 pose.position.z = 0.0;
167 tf2::Quaternion q;
168 q.setRPY(0, 0, p.yaw_);
169 pose.orientation = tf2::toMsg(q);
170
171 waypoints_.push_back(pose);
172 waypointsNames_.push_back(std::to_string(i++));
173 }
174}

References waypoints_, and waypointsNames_.

◆ stopWaitingResult()

void cl_nav2z::WaypointNavigator::stopWaitingResult ( )

Definition at line 73 of file waypoints_navigator.cpp.

74{
75 if (succeddedNav2ZClientConnection_.connected())
76 {
77 this->succeddedNav2ZClientConnection_.disconnect();
78 this->cancelledNav2ZClientConnection_.disconnect();
79 this->abortedNav2ZClientConnection_.disconnect();
80 }
81}

References abortedNav2ZClientConnection_, cancelledNav2ZClientConnection_, and succeddedNav2ZClientConnection_.

Referenced by cl_nav2z::CbNavigateNextWaypoint::onExit(), onGoalAborted(), onGoalCancelled(), and onGoalReached().

Here is the caller graph for this function:

Member Data Documentation

◆ abortedNav2ZClientConnection_

boost::signals2::connection cl_nav2z::WaypointNavigator::abortedNav2ZClientConnection_
private

Definition at line 103 of file waypoints_navigator.hpp.

Referenced by sendNextGoal(), and stopWaitingResult().

◆ cancelledNav2ZClientConnection_

boost::signals2::connection cl_nav2z::WaypointNavigator::cancelledNav2ZClientConnection_
private

Definition at line 104 of file waypoints_navigator.hpp.

Referenced by sendNextGoal(), and stopWaitingResult().

◆ client_

ClNav2Z* cl_nav2z::WaypointNavigator::client_

Definition at line 54 of file waypoints_navigator.hpp.

Referenced by onInitialize(), onOrthogonalAllocation(), and sendNextGoal().

◆ currentWaypoint_

long cl_nav2z::WaypointNavigator::currentWaypoint_

◆ onNavigationRequestAborted

smacc2::SmaccSignal<void()> cl_nav2z::WaypointNavigator::onNavigationRequestAborted

Definition at line 86 of file waypoints_navigator.hpp.

Referenced by onGoalAborted().

◆ onNavigationRequestCancelled

smacc2::SmaccSignal<void()> cl_nav2z::WaypointNavigator::onNavigationRequestCancelled

Definition at line 87 of file waypoints_navigator.hpp.

Referenced by onGoalCancelled().

◆ onNavigationRequestSucceded

smacc2::SmaccSignal<void()> cl_nav2z::WaypointNavigator::onNavigationRequestSucceded

Definition at line 85 of file waypoints_navigator.hpp.

Referenced by onGoalReached().

◆ succeddedNav2ZClientConnection_

boost::signals2::connection cl_nav2z::WaypointNavigator::succeddedNav2ZClientConnection_
private

Definition at line 102 of file waypoints_navigator.hpp.

Referenced by sendNextGoal(), and stopWaitingResult().

◆ waypoints_

std::vector<geometry_msgs::msg::Pose> cl_nav2z::WaypointNavigator::waypoints_
private

◆ waypointsEventDispatcher

WaypointEventDispatcher cl_nav2z::WaypointNavigator::waypointsEventDispatcher

Definition at line 52 of file waypoints_navigator.hpp.

Referenced by onGoalReached(), and onOrthogonalAllocation().

◆ waypointsNames_

std::vector<std::string> cl_nav2z::WaypointNavigator::waypointsNames_
private

Definition at line 100 of file waypoints_navigator.hpp.

Referenced by loadWayPointsFromFile2(), and setWaypoints().


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