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

#include <cb_absolute_rotate.hpp>

Inheritance diagram for cl_nav2z::CbAbsoluteRotate:
Inheritance graph
Collaboration diagram for cl_nav2z::CbAbsoluteRotate:
Collaboration graph

Public Member Functions

 CbAbsoluteRotate ()
 
 CbAbsoluteRotate (float absoluteGoalAngleDegree, float yawGoalTolerance=-1)
 
void onEntry () override
 
void onExit () override
 
- 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)
 
virtual void onEntry ()
 
virtual void onExit ()
 
virtual void executeOnEntry ()
 
virtual void executeOnExit ()
 

Public Attributes

std::shared_ptr< tf2_ros::Buffer > listener
 
float absoluteGoalAngleDegree
 
std::optional< float > yawGoalTolerance
 
std::optional< float > maxVelTheta
 
std::optional< SpinningPlannerspinningPlanner
 

Private Member Functions

void updateTemporalBehaviorParameters (bool undo)
 

Private Attributes

float oldYawTolerance
 
float oldMaxVelTheta
 
float oldMinVelTheta
 

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 ()
 
- 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 void dispose ()
 
virtual rclcpp::Node::SharedPtr getNode () const
 
virtual rclcpp::Logger getLogger () const
 
- 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_
 

Detailed Description

Definition at line 29 of file cb_absolute_rotate.hpp.

Constructor & Destructor Documentation

◆ CbAbsoluteRotate() [1/2]

cl_nav2z::CbAbsoluteRotate::CbAbsoluteRotate ( )

Definition at line 32 of file cb_absolute_rotate.cpp.

32{}

◆ CbAbsoluteRotate() [2/2]

cl_nav2z::CbAbsoluteRotate::CbAbsoluteRotate ( float  absoluteGoalAngleDegree,
float  yawGoalTolerance = -1 
)

Definition at line 33 of file cb_absolute_rotate.cpp.

34{
36
37 if (yaw_goal_tolerance >= 0)
38 {
39 this->yawGoalTolerance = yaw_goal_tolerance;
40 }
41}
std::optional< float > yawGoalTolerance

References absoluteGoalAngleDegree, and yawGoalTolerance.

Member Function Documentation

◆ onEntry()

void cl_nav2z::CbAbsoluteRotate::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Reimplemented in cl_nav2z::CbRotateLookAt.

Definition at line 43 of file cb_absolute_rotate.cpp.

44{
45 listener = std::make_shared<tf2_ros::Buffer>(getNode()->get_clock());
46 double goal_angle = this->absoluteGoalAngleDegree;
47
48 RCLCPP_INFO_STREAM(getLogger(), "[CbAbsoluteRotate] Absolute yaw Angle:" << goal_angle);
49
50 auto plannerSwitcher = this->nav2zClient_->getComponent<PlannerSwitcher>();
51 // this should work better with a coroutine and await
52 // this->plannerSwitcher_->setForwardPlanner();
53
55 {
56 plannerSwitcher->setPureSpinningPlanner();
57 }
58 else
59 {
60 plannerSwitcher->setDefaultPlanners();
61 }
62
64
66 auto referenceFrame = p->getReferenceFrame();
67 auto currentPoseMsg = p->toPoseMsg();
68
69 ClNav2Z::Goal goal;
70 goal.pose.header.frame_id = referenceFrame;
71 //goal.pose.header.stamp = getNode()->now();
72
73 auto targetAngle = goal_angle * M_PI / 180.0;
74 goal.pose.pose.position = currentPoseMsg.position;
75 tf2::Quaternion q;
76 q.setRPY(0, 0, targetAngle);
77 goal.pose.pose.orientation = tf2::toMsg(q);
78
79 auto odomTracker_ = nav2zClient_->getComponent<odom_tracker::OdomTracker>();
80 if (odomTracker_ != nullptr)
81 {
82 auto pathname = this->getCurrentState()->getName() + " - " + getName();
83 odomTracker_->pushPath(pathname);
84 odomTracker_->setStartPoint(p->toPoseStampedMsg());
85 odomTracker_->setWorkingMode(odom_tracker::WorkingMode::RECORD_PATH);
86 }
87
88 auto goalCheckerSwitcher = nav2zClient_->getComponent<GoalCheckerSwitcher>();
89 goalCheckerSwitcher->setGoalCheckerId("absolute_rotate_goal_checker");
90
91 RCLCPP_INFO_STREAM(
92 getLogger(),
93 "[" << getName() << "] current pose yaw: " << tf2::getYaw(currentPoseMsg.orientation));
94 RCLCPP_INFO_STREAM(
95 getLogger(),
96 "[" << getName() << "] goal pose yaw: " << tf2::getYaw(goal.pose.pose.orientation));
97 this->sendGoal(goal);
98}
std::optional< SpinningPlanner > spinningPlanner
void updateTemporalBehaviorParameters(bool undo)
std::shared_ptr< tf2_ros::Buffer > listener
const std::string & getReferenceFrame() const
Definition: cp_pose.hpp:76
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
TComponent * getComponent()
virtual std::string getName()=0

References absoluteGoalAngleDegree, smacc2::ISmaccClient::getComponent(), smacc2::ISmaccClientBehavior::getCurrentState(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccState::getName(), smacc2::ISmaccClientBehavior::getNode(), cl_nav2z::Pose::getReferenceFrame(), listener, cl_nav2z::CbNav2ZClientBehaviorBase::nav2zClient_, cl_nav2z::PureSpinning, cl_nav2z::odom_tracker::RECORD_PATH, cl_nav2z::CbNav2ZClientBehaviorBase::sendGoal(), cl_nav2z::GoalCheckerSwitcher::setGoalCheckerId(), cl_nav2z::PlannerSwitcher::setPureSpinningPlanner(), spinningPlanner, and updateTemporalBehaviorParameters().

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

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

◆ onExit()

void cl_nav2z::CbAbsoluteRotate::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 257 of file cb_absolute_rotate.cpp.

258{
260 {
261 }
262 else
263 {
264 }
265
267}

References cl_nav2z::PureSpinning, spinningPlanner, and updateTemporalBehaviorParameters().

Here is the call graph for this function:

◆ updateTemporalBehaviorParameters()

void cl_nav2z::CbAbsoluteRotate::updateTemporalBehaviorParameters ( bool  undo)
private

Definition at line 100 of file cb_absolute_rotate.cpp.

101{
102 auto log = this->getLogger();
103
104 std::string nodename = "/controller_server";
105
106 auto parameters_client =
107 std::make_shared<rclcpp::AsyncParametersClient>(this->getNode(), nodename);
108
109 RCLCPP_INFO_STREAM(
110 log, "[" << getName() << "] using a parameter client to update some controller parameters: "
111 << nodename << ". Waiting service.");
112 parameters_client->wait_for_service();
113
114 RCLCPP_INFO_STREAM(log, "[" << getName() << "] Service found: " << nodename << ".");
115
116 std::string localPlannerName;
117 std::vector<rclcpp::Parameter> parameters;
118
119 // dynamic_reconfigure::DoubleParameter yaw_goal_tolerance;
120 rclcpp::Parameter yaw_goal_tolerance("goal_checker.yaw_goal_tolerance");
121
122 rclcpp::Parameter max_vel_theta, min_vel_theta;
123
124 bool isRosBasePlanner = !spinningPlanner || *spinningPlanner == SpinningPlanner::Default;
125 bool isPureSpinningPlanner = spinningPlanner && *spinningPlanner == SpinningPlanner::PureSpinning;
126
127 // SELECTING CONTROLLER AND PARAMETERS NAME
128 if (isPureSpinningPlanner)
129 {
130 localPlannerName = "PureSpinningLocalPlanner";
131 max_vel_theta = rclcpp::Parameter(localPlannerName + ".max_angular_z_speed");
132 min_vel_theta = rclcpp::Parameter(localPlannerName + ".min_vel_theta");
133 }
134 else if (isRosBasePlanner)
135 {
136 localPlannerName = "FollowPath";
137 max_vel_theta = rclcpp::Parameter(localPlannerName + ".max_vel_theta");
138 min_vel_theta = rclcpp::Parameter(localPlannerName + ".min_vel_theta");
139 }
140
141 if (!undo)
142 {
144 {
145 // save old yaw tolerance
146 auto fut = parameters_client->get_parameters(
147 {localPlannerName + ".yaw_goal_tolerance"},
148 [&](auto futureParameters)
149 {
150 auto params = futureParameters.get();
151 oldYawTolerance = params[0].as_double();
152 });
153
154 // make synchronous
155 fut.get();
156
157 yaw_goal_tolerance = rclcpp::Parameter("goal_checker.yaw_goal_tolerance", *yawGoalTolerance);
158 parameters.push_back(yaw_goal_tolerance);
159 RCLCPP_INFO_STREAM(
160 getLogger(), "[" << getName()
161 << "] updating yaw tolerance local planner to: " << *yawGoalTolerance
162 << ", from previous value: " << this->oldYawTolerance);
163 }
164
165 if (maxVelTheta)
166 {
167 if (isRosBasePlanner)
168 {
169 // nh.getParam(nodename + "/" + localPlannerName+"/min_vel_theta", oldMinVelTheta);
170 // getCurrentState()->getParam(nodename + "/" + localPlannerName + "/max_vel_theta", oldMaxVelTheta);
171
172 // save old yaw tolerance
173 auto fut = parameters_client->get_parameters(
174 {localPlannerName + ".max_vel_theta"},
175 [&](auto futureParameters)
176 {
177 auto params = futureParameters.get();
178 oldMaxVelTheta = params[0].as_double();
179 });
180
181 // make synchronous
182 fut.get();
183 }
184
185 max_vel_theta = rclcpp::Parameter(localPlannerName + ".max_vel_theta", *maxVelTheta);
186 min_vel_theta = rclcpp::Parameter(localPlannerName + ".min_vel_theta", -*maxVelTheta);
187 parameters.push_back(max_vel_theta);
188 parameters.push_back(min_vel_theta);
189
190 RCLCPP_INFO_STREAM(
191 log, "[" << getName() << "] updating max vel theta local planner to: " << *maxVelTheta
192 << ", from previous value: " << this->oldMaxVelTheta);
193 RCLCPP_INFO_STREAM(
194 log, "[" << getName() << "] updating min vel theta local planner to: " << -*maxVelTheta
195 << ", from previous value: " << this->oldMinVelTheta);
196 }
197 }
198 else
199 {
201 {
202 yaw_goal_tolerance = rclcpp::Parameter("goal_checker.yaw_goal_tolerance", oldYawTolerance);
203 RCLCPP_INFO_STREAM(
204 log, "[" << getName() << "] restoring yaw tolerance local planner from: "
205 << *yawGoalTolerance << " , to previous value: " << this->oldYawTolerance);
206 }
207
208 if (maxVelTheta)
209 {
210 if (isRosBasePlanner)
211 {
212 max_vel_theta = rclcpp::Parameter(localPlannerName + ".max_vel_theta", oldMaxVelTheta);
213 min_vel_theta = rclcpp::Parameter(localPlannerName + ".max_vel_theta", oldMinVelTheta);
214 }
215
216 parameters.push_back(max_vel_theta);
217 parameters.push_back(min_vel_theta);
218 RCLCPP_INFO_STREAM(
219 log, "[" << getName() << "] restoring max vel theta local planner from: " << *maxVelTheta
220 << ", to previous value: " << this->oldMaxVelTheta);
221 RCLCPP_INFO_STREAM(
222 log, "[" << getName() << "] restoring min vel theta local planner from: " << -(*maxVelTheta)
223 << ", to previous value: " << this->oldMinVelTheta);
224 }
225 }
226
227 if (parameters.size())
228 {
229 std::stringstream ss;
230 ss << "Executing asynchronous request. Parameters to update: " << std::endl;
231 for (auto & p : parameters)
232 {
233 ss << p.get_name() << " - " << p.value_to_string() << std::endl;
234 }
235
236 RCLCPP_INFO_STREAM(getLogger(), "[CbAbsoluteRotate] " << ss.str());
237
238 auto futureResults = parameters_client->set_parameters(parameters);
239
240 int i = 0;
241 for (auto & res : futureResults.get())
242 {
243 RCLCPP_INFO_STREAM(
244 getLogger(), "[" << getName() << "] parameter result: " << parameters[i].get_name() << "="
245 << parameters[i].as_string() << ". Result: " << res.successful);
246 i++;
247 }
248
249 RCLCPP_INFO_STREAM(log, "[" << getName() << "] parameters updated");
250 }
251 else
252 {
253 RCLCPP_INFO_STREAM(log, "[" << getName() << "] skipping parameters update");
254 }
255}
std::optional< float > maxVelTheta

References cl_nav2z::Default, smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccClientBehavior::getNode(), maxVelTheta, oldMaxVelTheta, oldMinVelTheta, oldYawTolerance, cl_nav2z::PureSpinning, spinningPlanner, and yawGoalTolerance.

Referenced by onEntry(), and onExit().

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

Member Data Documentation

◆ absoluteGoalAngleDegree

float cl_nav2z::CbAbsoluteRotate::absoluteGoalAngleDegree

◆ listener

std::shared_ptr<tf2_ros::Buffer> cl_nav2z::CbAbsoluteRotate::listener

Definition at line 32 of file cb_absolute_rotate.hpp.

Referenced by onEntry().

◆ maxVelTheta

std::optional<float> cl_nav2z::CbAbsoluteRotate::maxVelTheta

Definition at line 36 of file cb_absolute_rotate.hpp.

Referenced by updateTemporalBehaviorParameters().

◆ oldMaxVelTheta

float cl_nav2z::CbAbsoluteRotate::oldMaxVelTheta
private

Definition at line 48 of file cb_absolute_rotate.hpp.

Referenced by updateTemporalBehaviorParameters().

◆ oldMinVelTheta

float cl_nav2z::CbAbsoluteRotate::oldMinVelTheta
private

Definition at line 49 of file cb_absolute_rotate.hpp.

Referenced by updateTemporalBehaviorParameters().

◆ oldYawTolerance

float cl_nav2z::CbAbsoluteRotate::oldYawTolerance
private

Definition at line 47 of file cb_absolute_rotate.hpp.

Referenced by updateTemporalBehaviorParameters().

◆ spinningPlanner

std::optional<SpinningPlanner> cl_nav2z::CbAbsoluteRotate::spinningPlanner

Definition at line 37 of file cb_absolute_rotate.hpp.

Referenced by onEntry(), onExit(), and updateTemporalBehaviorParameters().

◆ yawGoalTolerance

std::optional<float> cl_nav2z::CbAbsoluteRotate::yawGoalTolerance

Definition at line 35 of file cb_absolute_rotate.hpp.

Referenced by CbAbsoluteRotate(), and updateTemporalBehaviorParameters().


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