SMACC2
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | Protected Attributes | List of all members
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)
 
- Public Member Functions inherited from cl_nav2z::CbNav2ZClientBehaviorBase
virtual ~CbNav2ZClientBehaviorBase ()
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
- Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
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=false)
 

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
cl_nav2z::ClNav2Znav2zClient_
 
cl_nav2z::ClNav2Z::SmaccNavigateResultSignal::SharedPtr navigationCallback_
 
rclcpp_action::ResultCode navigationResult_
 
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 (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/3]

cl_nav2z::CbNavigateForward::CbNavigateForward ( )

Definition at line 36 of file cb_navigate_forward.cpp.

36{}

◆ CbNavigateForward() [2/3]

cl_nav2z::CbNavigateForward::CbNavigateForward ( float  forwardDistance)

Definition at line 35 of file cb_navigate_forward.cpp.

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

◆ CbNavigateForward() [3/3]

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

Definition at line 38 of file cb_navigate_forward.cpp.

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

◆ ~CbNavigateForward()

cl_nav2z::CbNavigateForward::~CbNavigateForward ( )
virtual

Definition at line 40 of file cb_navigate_forward.cpp.

40{}

Member Function Documentation

◆ onEntry()

void cl_nav2z::CbNavigateForward::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 57 of file cb_navigate_forward.cpp.

58{
60 {
62
63 RCLCPP_INFO_STREAM(
64 getLogger(), "[" << getName() << "] Straight motion distance: " << *forwardDistance_);
65 }
66
67 // get current pose
68 auto p = nav2zClient_->getComponent<Pose>();
69 auto referenceFrame = p->getReferenceFrame();
70 auto currentPoseMsg = p->toPoseMsg();
71
72 RCLCPP_INFO_STREAM(
73 getLogger(), "[" << getName() << "]"
74 << "current pose: " << currentPoseMsg);
75
76 // force global orientation if it is requested
78 {
79 currentPoseMsg.orientation = *(options.forceInitialOrientation);
80 RCLCPP_WARN_STREAM(
81 getLogger(),
82 "[" << getName() << "]"
83 << "Forcing initial straight motion orientation: " << currentPoseMsg.orientation);
84 }
85
86 tf2::Transform currentPose;
87 tf2::fromMsg(currentPoseMsg, currentPose);
88
89 tf2::Transform targetPose;
90 if (goalPose_)
91 {
92 tf2::fromMsg(goalPose_->pose, targetPose);
93 }
94 else if (forwardDistance_)
95 {
96 // compute forward goal pose
97 tf2::Transform forwardDeltaTransform;
98 forwardDeltaTransform.setIdentity();
99 forwardDeltaTransform.setOrigin(tf2::Vector3(*forwardDistance_, 0, 0));
100
101 targetPose = currentPose * forwardDeltaTransform;
102 }
103 else
104 {
105 RCLCPP_WARN_STREAM(
106 getLogger(),
107 "[" << getName() << "]"
108 << "No goal Pose or Distance is specified. Aborting. No action request is sent."
109 << currentPoseMsg.orientation);
110
111 return;
112 }
113
114 // action goal
115 ClNav2Z::Goal goal;
116 goal.pose.header.frame_id = referenceFrame;
117 //goal.pose.header.stamp = getNode()->now();
118 tf2::toMsg(targetPose, goal.pose.pose);
119 RCLCPP_INFO_STREAM(
120 getLogger(), "[" << getName() << "]"
121 << " TARGET POSE FORWARD: " << goal.pose.pose);
122
123 // current pose
124 geometry_msgs::msg::PoseStamped currentStampedPoseMsg;
125 currentStampedPoseMsg.header.frame_id = referenceFrame;
126 currentStampedPoseMsg.header.stamp =
127 getNode()->now(); // probably it is better avoid setting that goal timestamp
128
129 tf2::toMsg(currentPose, currentStampedPoseMsg.pose);
130
131 odomTracker_ = nav2zClient_->getComponent<CpOdomTracker>();
132 if (odomTracker_ != nullptr)
133 {
134 auto pathname = this->getCurrentState()->getName() + " - " + getName();
135 odomTracker_->pushPath(pathname);
136 odomTracker_->setStartPoint(currentStampedPoseMsg);
138 odomTracker_->setWorkingMode(WorkingMode::RECORD_PATH);
139 }
140
141 auto plannerSwitcher = nav2zClient_->getComponent<CpPlannerSwitcher>();
142 plannerSwitcher->setForwardPlanner();
143
144 auto goalCheckerSwitcher = nav2zClient_->getComponent<CpGoalCheckerSwitcher>();
145 goalCheckerSwitcher->setGoalCheckerId("forward_goal_checker");
146
147 this->sendGoal(goal);
148}
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)
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::ISmaccClient::getComponent(), smacc2::ISmaccClientBehavior::getCurrentState(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccState::getName(), smacc2::ISmaccClientBehavior::getNode(), cl_nav2z::Pose::getReferenceFrame(), goalPose_, cl_nav2z::CbNav2ZClientBehaviorBase::nav2zClient_, odomTracker_, options, cl_nav2z::odom_tracker::CpOdomTracker::pushPath(), 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(), and cl_nav2z::odom_tracker::CpOdomTracker::setWorkingMode().

Here is the call graph for this function:

◆ onExit()

void cl_nav2z::CbNavigateForward::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 150 of file cb_navigate_forward.cpp.

151{
152 if (odomTracker_)
153 {
154 this->odomTracker_->setWorkingMode(WorkingMode::IDLE);
155 }
156}

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

Here is the call graph for this function:

◆ setForwardDistance()

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

Definition at line 42 of file cb_navigate_forward.cpp.

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

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:

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: