SMACC2
Loading...
Searching...
No Matches
cl_nav2z::CbNavigateForward Class Reference

#include <cb_navigate_forward.hpp>

Inheritance diagram for cl_nav2z::CbNavigateForward:
Inheritance graph
Collaboration diagram for cl_nav2z::CbNavigateForward:
Collaboration graph

Public Member Functions

 CbNavigateForward ()
 
 CbNavigateForward (float forwardDistance)
 
 CbNavigateForward (geometry_msgs::msg::PoseStamped goalPosition)
 
virtual ~CbNavigateForward ()
 
void onEntry () override
 
void onExit () override
 
void setForwardDistance (float distance_meters)
 
 CbNavigateForward ()
 
 CbNavigateForward (float forwardDistance)
 
 CbNavigateForward (geometry_msgs::msg::PoseStamped goalPosition)
 
virtual ~CbNavigateForward ()
 
void onEntry () override
 
void onExit () override
 
void setForwardDistance (float distance_meters)
 
- Public Member Functions inherited from cl_nav2z::CbNav2ZClientBehaviorBase
virtual ~CbNav2ZClientBehaviorBase ()
 
template<typename TOrthogonal , typename TSourceObject >
void onStateOrthogonalAllocation ()
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
virtual ~CbNav2ZClientBehaviorBase ()
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
template<typename TOrthogonal , typename TSourceObject >
void onStateOrthogonalAllocation ()
 
- Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
template<typename TOrthogonal , typename TSourceObject >
void onStateOrthogonalAllocation ()
 
virtual ~SmaccAsyncClientBehavior ()
 
template<typename TCallback , typename T >
boost::signals2::connection onSuccess (TCallback callback, T *object)
 
template<typename TCallback , typename T >
boost::signals2::connection onFinished (TCallback callback, T *object)
 
template<typename TCallback , typename T >
boost::signals2::connection onFailure (TCallback callback, T *object)
 
void requestForceFinish ()
 
void executeOnEntry () override
 
void executeOnExit () override
 
void waitOnEntryThread (bool requestFinish)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onSuccess (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFinished (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFailure (TCallbackMethod callback, T *object)
 
- Public Member Functions inherited from smacc2::ISmaccClientBehavior
 ISmaccClientBehavior ()
 
virtual ~ISmaccClientBehavior ()
 
ISmaccStateMachinegetStateMachine ()
 
std::string getName () const
 
template<typename SmaccClientType >
void requiresClient (SmaccClientType *&storage)
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage, bool throwExceptionIfNotExist)
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
 

Public Attributes

CbNavigateForwardOptions options
 

Protected Attributes

odom_tracker::CpOdomTrackerodomTracker_
 
std::optional< geometry_msgs::msg::PoseStamped > goalPose_
 
std::optional< float > forwardDistance_
 
- Protected Attributes inherited from cl_nav2z::CbNav2ZClientBehaviorBase
components::CpNav2ActionInterfacenav2ActionInterface_ = nullptr
 
smacc2::client_core_components::CpActionClient< nav2_msgs::action::NavigateToPose > * actionClient_ = nullptr
 
rclcpp_action::ResultCode navigationResult_
 
cl_nav2z::ClNav2Znav2zClient_
 
cl_nav2z::ClNav2Z::SmaccNavigateResultSignal::SharedPtr navigationCallback_
 
std::shared_future< std::shared_ptr< rclcpp_action::ClientGoalHandle< nav2_msgs::action::NavigateToPose > > > goalHandleFuture_
 

Additional Inherited Members

- Protected Member Functions inherited from cl_nav2z::CbNav2ZClientBehaviorBase
void sendGoal (nav2_msgs::action::NavigateToPose::Goal &goal)
 
void cancelGoal ()
 
template<typename T >
boost::signals2::connection onNavigationSucceeded (void(T::*callback)(const components::CpNav2ActionInterface::WrappedResult &), T *object)
 
template<typename T >
boost::signals2::connection onNavigationAborted (void(T::*callback)(const components::CpNav2ActionInterface::WrappedResult &), T *object)
 
template<typename T >
boost::signals2::connection onNavigationCancelled (void(T::*callback)(const components::CpNav2ActionInterface::WrappedResult &), T *object)
 
virtual void onNavigationResult (const components::CpNav2ActionInterface::WrappedResult &)
 
virtual void onNavigationActionSuccess (const components::CpNav2ActionInterface::WrappedResult &)
 
virtual void onNavigationActionAbort (const components::CpNav2ActionInterface::WrappedResult &)
 
void sendGoal (ClNav2Z::Goal &goal)
 
void cancelGoal ()
 
bool isOwnActionResponse (const ClNav2Z::WrappedResult &)
 
virtual void onNavigationResult (const ClNav2Z::WrappedResult &)
 
virtual void onNavigationActionSuccess (const ClNav2Z::WrappedResult &)
 
virtual void onNavigationActionAbort (const ClNav2Z::WrappedResult &)
 
- Protected Member Functions inherited from smacc2::SmaccAsyncClientBehavior
void postSuccessEvent ()
 
void postFailureEvent ()
 
virtual void dispose () override
 
bool isShutdownRequested ()
 onEntry is executed in a new thread. However the current state cannot be left until the onEntry thread finishes. This flag can be checked from the onEntry thread to force finishing the thread.
 
- Protected Member Functions inherited from smacc2::ISmaccClientBehavior
virtual void runtimeConfigure ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
ISmaccStategetCurrentState ()
 
virtual rclcpp::Node::SharedPtr getNode () const
 
virtual rclcpp::Logger getLogger () const
 

Detailed Description

Definition at line 48 of file cb_navigate_forward.hpp.

Constructor & Destructor Documentation

◆ CbNavigateForward() [1/6]

cl_nav2z::CbNavigateForward::CbNavigateForward ( )

Definition at line 37 of file cb_navigate_forward.cpp.

37{}

◆ CbNavigateForward() [2/6]

cl_nav2z::CbNavigateForward::CbNavigateForward ( float forwardDistance)

Definition at line 36 of file cb_navigate_forward.cpp.

36: forwardDistance_(distance_meters) {}
std::optional< float > forwardDistance_

◆ CbNavigateForward() [3/6]

cl_nav2z::CbNavigateForward::CbNavigateForward ( geometry_msgs::msg::PoseStamped goalPosition)

Definition at line 39 of file cb_navigate_forward.cpp.

39: goalPose_(goal) {}
std::optional< geometry_msgs::msg::PoseStamped > goalPose_

◆ ~CbNavigateForward() [1/2]

cl_nav2z::CbNavigateForward::~CbNavigateForward ( )
virtual

Definition at line 41 of file cb_navigate_forward.cpp.

41{}

◆ CbNavigateForward() [4/6]

cl_nav2z::CbNavigateForward::CbNavigateForward ( )

◆ CbNavigateForward() [5/6]

cl_nav2z::CbNavigateForward::CbNavigateForward ( float forwardDistance)

◆ CbNavigateForward() [6/6]

cl_nav2z::CbNavigateForward::CbNavigateForward ( geometry_msgs::msg::PoseStamped goalPosition)

◆ ~CbNavigateForward() [2/2]

virtual cl_nav2z::CbNavigateForward::~CbNavigateForward ( )
virtual

Member Function Documentation

◆ onEntry() [1/2]

void cl_nav2z::CbNavigateForward::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 58 of file cb_navigate_forward.cpp.

59{
61 {
63
64 RCLCPP_INFO_STREAM(
65 getLogger(), "[" << getName() << "] Straight motion distance: " << *forwardDistance_);
66 }
67
68 // get current pose
69 CpPose * p;
70 this->requiresComponent(p, ComponentRequirement::HARD);
71
72 auto referenceFrame = p->getReferenceFrame();
73 auto currentPoseMsg = p->toPoseMsg();
74
75 RCLCPP_INFO_STREAM(
76 getLogger(), "[" << getName() << "]"
77 << "current pose: " << currentPoseMsg);
78
79 // force global orientation if it is requested
81 {
82 currentPoseMsg.orientation = *(options.forceInitialOrientation);
83 RCLCPP_WARN_STREAM(
84 getLogger(),
85 "[" << getName() << "]"
86 << "Forcing initial straight motion orientation: " << currentPoseMsg.orientation);
87 }
88
89 tf2::Transform currentPose;
90 tf2::fromMsg(currentPoseMsg, currentPose);
91
92 tf2::Transform targetPose;
93 if (goalPose_)
94 {
95 tf2::fromMsg(goalPose_->pose, targetPose);
96 }
97 else if (forwardDistance_)
98 {
99 // compute forward goal pose
100 tf2::Transform forwardDeltaTransform;
101 forwardDeltaTransform.setIdentity();
102 forwardDeltaTransform.setOrigin(tf2::Vector3(*forwardDistance_, 0, 0));
103
104 targetPose = currentPose * forwardDeltaTransform;
105 }
106 else
107 {
108 RCLCPP_WARN_STREAM(
109 getLogger(),
110 "[" << getName() << "]"
111 << "No goal Pose or Distance is specified. Aborting. No action request is sent."
112 << currentPoseMsg.orientation);
113
114 return;
115 }
116
117 // action goal
118 nav2_msgs::action::NavigateToPose::Goal goal;
119 goal.pose.header.frame_id = referenceFrame;
120 //goal.pose.header.stamp = getNode()->now();
121 tf2::toMsg(targetPose, goal.pose.pose);
122 RCLCPP_INFO_STREAM(
123 getLogger(), "[" << getName() << "]"
124 << " TARGET POSE FORWARD: " << goal.pose.pose);
125
126 // current pose
127 geometry_msgs::msg::PoseStamped currentStampedPoseMsg;
128 currentStampedPoseMsg.header.frame_id = referenceFrame;
129 currentStampedPoseMsg.header.stamp =
130 getNode()->now(); // probably it is better avoid setting that goal timestamp
131
132 tf2::toMsg(currentPose, currentStampedPoseMsg.pose);
133
134 requiresComponent(odomTracker_, ComponentRequirement::SOFT);
135
136 if (odomTracker_ != nullptr)
137 {
138 auto pathname = this->getCurrentState()->getName() + " - " + getName();
139 odomTracker_->pushPath(pathname);
140 odomTracker_->setStartPoint(currentStampedPoseMsg);
142 odomTracker_->setWorkingMode(WorkingMode::RECORD_PATH);
143 }
144
145 CpPlannerSwitcher * plannerSwitcher;
146 this->requiresComponent(plannerSwitcher, ComponentRequirement::HARD);
147 plannerSwitcher->setForwardPlanner();
148
149 CpGoalCheckerSwitcher * goalCheckerSwitcher;
150 this->requiresComponent(goalCheckerSwitcher, ComponentRequirement::HARD);
151 goalCheckerSwitcher->setGoalCheckerId("forward_goal_checker");
152
153 this->sendGoal(goal);
154}
void sendGoal(nav2_msgs::action::NavigateToPose::Goal &goal)
CbNavigateForwardOptions options
void setForwardDistance(float distance_meters)
odom_tracker::CpOdomTracker * odomTracker_
void setCurrentMotionGoal(const geometry_msgs::msg::PoseStamped &pose)
void setWorkingMode(WorkingMode workingMode)
void setStartPoint(const geometry_msgs::msg::PoseStamped &pose)
void requiresComponent(SmaccComponentType *&storage, bool throwExceptionIfNotExist)
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
virtual std::string getName()=0
std::optional< geometry_msgs::msg::Quaternion > forceInitialOrientation

References cl_nav2z::CbNavigateForwardOptions::forceInitialOrientation, forwardDistance_, smacc2::ISmaccClientBehavior::getCurrentState(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccState::getName(), smacc2::ISmaccClientBehavior::getNode(), cl_nav2z::CpPose::getReferenceFrame(), goalPose_, odomTracker_, options, cl_nav2z::odom_tracker::CpOdomTracker::pushPath(), smacc2::ISmaccClientBehavior::requiresComponent(), cl_nav2z::CbNav2ZClientBehaviorBase::sendGoal(), cl_nav2z::odom_tracker::CpOdomTracker::setCurrentMotionGoal(), setForwardDistance(), cl_nav2z::CpPlannerSwitcher::setForwardPlanner(), cl_nav2z::CpGoalCheckerSwitcher::setGoalCheckerId(), cl_nav2z::odom_tracker::CpOdomTracker::setStartPoint(), cl_nav2z::odom_tracker::CpOdomTracker::setWorkingMode(), and cl_nav2z::CpPose::toPoseMsg().

Here is the call graph for this function:

◆ onEntry() [2/2]

void cl_nav2z::CbNavigateForward::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

◆ onExit() [1/2]

void cl_nav2z::CbNavigateForward::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 156 of file cb_navigate_forward.cpp.

157{
158 if (odomTracker_)
159 {
160 this->odomTracker_->setWorkingMode(WorkingMode::IDLE);
161 }
162}

References odomTracker_, and cl_nav2z::odom_tracker::CpOdomTracker::setWorkingMode().

Here is the call graph for this function:

◆ onExit() [2/2]

void cl_nav2z::CbNavigateForward::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

◆ setForwardDistance() [1/2]

void cl_nav2z::CbNavigateForward::setForwardDistance ( float distance_meters)

Definition at line 43 of file cb_navigate_forward.cpp.

44{
45 if (distance_meters < 0)
46 {
47 RCLCPP_INFO_STREAM(
48 getLogger(), "[" << getName() << "] negative forward distance: " << distance_meters
49 << ". Resetting to 0.");
50 distance_meters = 0;
51 }
52 forwardDistance_ = distance_meters;
53
54 RCLCPP_INFO_STREAM(
55 getLogger(), "[" << getName() << "] setting fw motion distance: " << *forwardDistance_);
56}

References forwardDistance_, smacc2::ISmaccClientBehavior::getLogger(), and smacc2::ISmaccClientBehavior::getName().

Referenced by onEntry().

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

◆ setForwardDistance() [2/2]

void cl_nav2z::CbNavigateForward::setForwardDistance ( float distance_meters)

Member Data Documentation

◆ forwardDistance_

std::optional< float > cl_nav2z::CbNavigateForward::forwardDistance_
protected

Definition at line 77 of file cb_navigate_forward.hpp.

Referenced by onEntry(), and setForwardDistance().

◆ goalPose_

std::optional< geometry_msgs::msg::PoseStamped > cl_nav2z::CbNavigateForward::goalPose_
protected

Definition at line 75 of file cb_navigate_forward.hpp.

Referenced by onEntry().

◆ odomTracker_

odom_tracker::CpOdomTracker * cl_nav2z::CbNavigateForward::odomTracker_
protected

Definition at line 73 of file cb_navigate_forward.hpp.

Referenced by onEntry(), and onExit().

◆ options

CbNavigateForwardOptions cl_nav2z::CbNavigateForward::options

Definition at line 51 of file cb_navigate_forward.hpp.

Referenced by onEntry().


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