SMACC2
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
cl_nav2z::CpWaypointNavigator Class Reference

#include <cp_waypoints_navigator.hpp>

Inheritance diagram for cl_nav2z::CpWaypointNavigator:
Inheritance graph
Collaboration diagram for cl_nav2z::CpWaypointNavigator:
Collaboration graph

Public Member Functions

 CpWaypointNavigator ()
 
void onInitialize () override
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
std::optional< std::shared_future< std::shared_ptr< rclcpp_action::ClientGoalHandle< nav2_msgs::action::NavigateToPose > > > > sendNextGoal (std::optional< NavigateNextWaypointOptions > options=std::nullopt, cl_nav2z::ClNav2Z::SmaccNavigateResultSignal::WeakPtr callback=cl_nav2z::ClNav2Z::SmaccNavigateResultSignal::WeakPtr())
 
void stopWaitingResult ()
 
- Public Member Functions inherited from cl_nav2z::CpWaypointNavigatorBase
 CpWaypointNavigatorBase ()
 
virtual ~CpWaypointNavigatorBase ()
 
void onInitialize () override
 
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)
 
const std::vector< geometry_msgs::msg::Pose > & getWaypoints () const
 
const std::vector< std::string > & getWaypointNames () const
 
std::optional< geometry_msgs::msg::Pose > getNamedPose (std::string name) const
 
geometry_msgs::msg::Pose getPose (int index) const
 
geometry_msgs::msg::Pose getCurrentPose () const
 
long getCurrentWaypointIndex () const
 
std::optional< std::string > getCurrentWaypointName () const
 
void rewind (int count)
 
void forward (int count)
 
void seekName (std::string name)
 
void loadWaypointsFromYamlParameter (std::string parameter_name, std::string yaml_file_package_name)
 
void notifyGoalReached ()
 
- Public Member Functions inherited from smacc2::ISmaccComponent
 ISmaccComponent ()
 
virtual ~ISmaccComponent ()
 
virtual std::string getName () const
 

Public Attributes

ClNav2Zclient_
 
smacc2::SmaccSignal< void()> onNavigationRequestSucceded
 
smacc2::SmaccSignal< void()> onNavigationRequestAborted
 
smacc2::SmaccSignal< void()> onNavigationRequestCancelled
 
- Public Attributes inherited from cl_nav2z::CpWaypointNavigatorBase
WaypointEventDispatcher waypointsEventDispatcher
 
long currentWaypoint_
 

Private Member Functions

void onNavigationResult (const ClNav2Z::WrappedResult &r)
 
void onGoalReached (const ClNav2Z::WrappedResult &res)
 
void onGoalCancelled (const ClNav2Z::WrappedResult &)
 
void onGoalAborted (const ClNav2Z::WrappedResult &)
 

Private Attributes

boost::signals2::connection succeddedNav2ZClientConnection_
 
boost::signals2::connection abortedNav2ZClientConnection_
 
boost::signals2::connection cancelledNav2ZClientConnection_
 

Additional Inherited Members

- Protected Member Functions inherited from cl_nav2z::CpWaypointNavigatorBase
void insertWaypoint (int index, geometry_msgs::msg::Pose &newpose)
 
void removeWaypoint (int index)
 
- Protected Member Functions inherited from smacc2::ISmaccComponent
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, bool throwExceptionIfNotExist=false)
 
template<typename TComponent >
void requiresComponent (std::string name, TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist=false)
 
template<typename TClient >
void requiresClient (TClient *&requiredClientStorage)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentTypecreateSiblingComponent (TArgs... targs)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentTypecreateSiblingNamedComponent (std::string name, TArgs... targs)
 
rclcpp::Node::SharedPtr getNode ()
 
rclcpp::Logger getLogger () const
 
ISmaccStateMachinegetStateMachine ()
 
- Protected Attributes inherited from cl_nav2z::CpWaypointNavigatorBase
std::vector< geometry_msgs::msg::Pose > waypoints_
 
std::vector< std::string > waypointsNames_
 
- Protected Attributes inherited from smacc2::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

Definition at line 46 of file cp_waypoints_navigator.hpp.

Constructor & Destructor Documentation

◆ CpWaypointNavigator()

cl_nav2z::CpWaypointNavigator::CpWaypointNavigator ( )

Definition at line 42 of file cp_waypoints_navigator.cpp.

42{}

Member Function Documentation

◆ onGoalAborted()

void cl_nav2z::CpWaypointNavigator::onGoalAborted ( const ClNav2Z::WrappedResult )
private

Definition at line 55 of file cp_waypoints_navigator.cpp.

References onNavigationRequestAborted, and stopWaitingResult().

Referenced by onNavigationResult().

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

◆ onGoalCancelled()

void cl_nav2z::CpWaypointNavigator::onGoalCancelled ( const ClNav2Z::WrappedResult )
private

Definition at line 48 of file cp_waypoints_navigator.cpp.

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

References onNavigationRequestCancelled, and stopWaitingResult().

Referenced by onNavigationResult().

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

◆ onGoalReached()

void cl_nav2z::CpWaypointNavigator::onGoalReached ( const ClNav2Z::WrappedResult res)
private

Definition at line 62 of file cp_waypoints_navigator.cpp.

63{
66 RCLCPP_WARN(
67 getLogger(), "[CpWaypointNavigator] Goal result received, incrementing waypoint index: %ld",
70
71 this->notifyGoalReached();
72
74}
smacc2::SmaccSignal< void()> onNavigationRequestSucceded
rclcpp::Logger getLogger() const

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

Referenced by onNavigationResult().

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

◆ onInitialize()

void cl_nav2z::CpWaypointNavigator::onInitialize ( )
overridevirtual

Reimplemented from smacc2::ISmaccComponent.

Definition at line 46 of file cp_waypoints_navigator.cpp.

46{ client_ = dynamic_cast<ClNav2Z *>(owner_); }
ISmaccClient * owner_
Definition component.hpp:83
namespace cl_nav2z class ClNav2Z

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

◆ onNavigationResult()

void cl_nav2z::CpWaypointNavigator::onNavigationResult ( const ClNav2Z::WrappedResult r)
private

Definition at line 308 of file cp_waypoints_navigator.cpp.

309{
310 if (r.code == rclcpp_action::ResultCode::SUCCEEDED)
311 {
312 this->onGoalReached(r);
313 }
314 else if (r.code == rclcpp_action::ResultCode::ABORTED)
315 {
316 this->onGoalAborted(r);
317 }
318 else if (r.code == rclcpp_action::ResultCode::CANCELED)
319 {
320 this->onGoalCancelled(r);
321 }
322 else
323 {
324 this->onGoalAborted(r);
325 }
326}
void onGoalAborted(const ClNav2Z::WrappedResult &)
void onGoalCancelled(const ClNav2Z::WrappedResult &)
void onGoalReached(const ClNav2Z::WrappedResult &res)

References onGoalAborted(), onGoalCancelled(), and onGoalReached().

Referenced by sendNextGoal().

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

◆ onOrthogonalAllocation()

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

Definition at line 56 of file cp_waypoints_navigator.hpp.

57 {
58 waypointsEventDispatcher.initialize<TSourceObject, TOrthogonal>(client_);
59 }

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

Here is the call graph for this function:

◆ sendNextGoal()

std::optional< std::shared_future< std::shared_ptr< rclcpp_action::ClientGoalHandle< nav2_msgs::action::NavigateToPose > > > > cl_nav2z::CpWaypointNavigator::sendNextGoal ( std::optional< NavigateNextWaypointOptions options = std::nullopt,
cl_nav2z::ClNav2Z::SmaccNavigateResultSignal::WeakPtr  callback = cl_nav2z::ClNav2Z::SmaccNavigateResultSignal::WeakPtr() 
)

Definition at line 192 of file cp_waypoints_navigator.cpp.

195{
196 if (currentWaypoint_ >= 0 && currentWaypoint_ < (int)waypoints_.size())
197 {
198 auto & next = waypoints_[currentWaypoint_];
199
200 std::string nextName;
201 if ((long)waypointsNames_.size() > currentWaypoint_)
202 {
204 RCLCPP_INFO(
205 getLogger(), "[CpWaypointNavigator] sending goal, waypoint: %s", nextName.c_str());
206 }
207 else
208 {
209 RCLCPP_INFO(
210 getLogger(), "[CpWaypointNavigator] sending goal, waypoint: %ld", currentWaypoint_);
211 }
212
213 ClNav2Z::Goal goal;
215 auto pose = p->toPoseMsg();
216
217 // configuring goal
218 goal.pose.header.frame_id = p->getReferenceFrame();
219 //goal.pose.header.stamp = getNode()->now();
220 goal.pose.pose = next;
221
222 auto plannerSwitcher = client_->getComponent<CpPlannerSwitcher>();
223 plannerSwitcher->setDefaultPlanners(false);
224 if (options && options->controllerName_)
225 {
226 RCLCPP_WARN(
227 getLogger(), "[WaypointsNavigator] override controller: %s",
228 options->controllerName_->c_str());
229
230 plannerSwitcher->setDesiredController(*options->controllerName_);
231 }
232 else
233 {
234 RCLCPP_WARN(getLogger(), "[WaypointsNavigator] Configuring default planners");
235 }
236
237 auto goalCheckerSwitcher = client_->getComponent<CpGoalCheckerSwitcher>();
238
239 if (options && options->goalCheckerName_)
240 {
241 RCLCPP_WARN(
242 getLogger(), "[WaypointsNavigator] override goal checker: %s",
243 options->goalCheckerName_->c_str());
244
245 goalCheckerSwitcher->setGoalCheckerId(*options->goalCheckerName_);
246 }
247 else
248 {
249 RCLCPP_WARN(getLogger(), "[WaypointsNavigator] Configuring default goal checker");
250 goalCheckerSwitcher->setGoalCheckerId("goal_checker");
251 }
252
253 plannerSwitcher->commitPublish();
254
255 // publish stuff
256 // rclcpp::sleep_for(5s);
257
258 RCLCPP_INFO(getLogger(), "[WaypointsNavigator] Getting odom tracker");
260 if (odomTracker != nullptr)
261 {
262 RCLCPP_INFO(getLogger(), "[WaypointsNavigator] Storing path in odom tracker");
263
264 auto pathname = this->owner_->getStateMachine()->getCurrentState()->getName() + " - " +
265 getName() + " - " + nextName;
266 odomTracker->pushPath(pathname);
267 odomTracker->setStartPoint(pose);
268 odomTracker->setWorkingMode(cl_nav2z::odom_tracker::WorkingMode::RECORD_PATH);
269 }
270
271 // SEND GOAL
272 // if (!succeddedNav2ZClientConnection_.connected())
273 // {
274 // this->succeddedNav2ZClientConnection_ =
275 // client_->onSucceeded(&WaypointNavigator::onGoalReached, this);
276 // this->cancelledNav2ZClientConnection_ =
277 // client_->onAborted(&WaypointNavigator::onGoalCancelled, this);
278 // this->abortedNav2ZClientConnection_ =
279 // client_->onCancelled(&WaypointNavigator::onGoalAborted, this);
280 // }
281
282 auto callbackptr = resultCallback.lock();
284 *callbackptr, &CpWaypointNavigator::onNavigationResult, this);
285
286 return client_->sendGoal(goal, resultCallback);
287 }
288 else
289 {
290 RCLCPP_WARN(
291 getLogger(),
292 "[CpWaypointsNavigator] All waypoints were consumed. There is no more waypoints available.");
293 }
294
295 return std::nullopt;
296}
std::vector< geometry_msgs::msg::Pose > waypoints_
boost::signals2::connection succeddedNav2ZClientConnection_
void onNavigationResult(const ClNav2Z::WrappedResult &r)
geometry_msgs::msg::Pose toPoseMsg()
Definition cp_pose.hpp:57
ISmaccStateMachine * getStateMachine()
ISmaccStateMachine * getStateMachine()
virtual std::string getName() const
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
virtual std::string getName()=0
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal, typename SmaccActionResultSignal::WeakPtr resultCallback=typename SmaccActionResultSignal::WeakPtr())

References client_, smacc2::ISmaccStateMachine::createSignalConnection(), cl_nav2z::CpWaypointNavigatorBase::currentWaypoint_, smacc2::ISmaccClient::getComponent(), smacc2::ISmaccStateMachine::getCurrentState(), smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), smacc2::ISmaccState::getName(), smacc2::ISmaccComponent::getStateMachine(), smacc2::ISmaccClient::getStateMachine(), onNavigationResult(), smacc2::ISmaccComponent::owner_, cl_nav2z::odom_tracker::RECORD_PATH, smacc2::client_bases::SmaccActionClientBase< ActionType >::sendGoal(), cl_nav2z::CpPlannerSwitcher::setDefaultPlanners(), succeddedNav2ZClientConnection_, cl_nav2z::Pose::toPoseMsg(), cl_nav2z::CpWaypointNavigatorBase::waypoints_, and cl_nav2z::CpWaypointNavigatorBase::waypointsNames_.

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

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

◆ stopWaitingResult()

void cl_nav2z::CpWaypointNavigator::stopWaitingResult ( )

Definition at line 180 of file cp_waypoints_navigator.cpp.

181{
182 if (succeddedNav2ZClientConnection_.connected())
183 {
184 this->succeddedNav2ZClientConnection_.disconnect();
185 this->cancelledNav2ZClientConnection_.disconnect();
186 this->abortedNav2ZClientConnection_.disconnect();
187 }
188}
boost::signals2::connection abortedNav2ZClientConnection_
boost::signals2::connection cancelledNav2ZClientConnection_

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::CpWaypointNavigator::abortedNav2ZClientConnection_
private

Definition at line 82 of file cp_waypoints_navigator.hpp.

Referenced by stopWaitingResult().

◆ cancelledNav2ZClientConnection_

boost::signals2::connection cl_nav2z::CpWaypointNavigator::cancelledNav2ZClientConnection_
private

Definition at line 83 of file cp_waypoints_navigator.hpp.

Referenced by stopWaitingResult().

◆ client_

ClNav2Z* cl_nav2z::CpWaypointNavigator::client_

Definition at line 49 of file cp_waypoints_navigator.hpp.

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

◆ onNavigationRequestAborted

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

Definition at line 71 of file cp_waypoints_navigator.hpp.

Referenced by onGoalAborted().

◆ onNavigationRequestCancelled

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

Definition at line 72 of file cp_waypoints_navigator.hpp.

Referenced by onGoalCancelled().

◆ onNavigationRequestSucceded

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

Definition at line 70 of file cp_waypoints_navigator.hpp.

Referenced by onGoalReached().

◆ succeddedNav2ZClientConnection_

boost::signals2::connection cl_nav2z::CpWaypointNavigator::succeddedNav2ZClientConnection_
private

Definition at line 81 of file cp_waypoints_navigator.hpp.

Referenced by sendNextGoal(), and stopWaitingResult().


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