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

#include <cb_navigate_backwards.hpp>

Inheritance diagram for cl_nav2z::CbNavigateBackwards:
Inheritance graph
Collaboration diagram for cl_nav2z::CbNavigateBackwards:
Collaboration graph

Public Member Functions

 CbNavigateBackwards (float backwardDistance)
 
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)
 
- 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)
 

Public Attributes

float backwardDistance
 
std::optional< float > backwardSpeed
 
std::optional< std::string > goalChecker_
 
cl_nav2z::odom_tracker::OdomTrackerodomTracker_
 

Additional Inherited Members

- 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 ()
 
virtual void onEntry ()
 
virtual void onExit ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
ISmaccStategetCurrentState ()
 
virtual void dispose ()
 
virtual rclcpp::Node::SharedPtr getNode ()
 
virtual rclcpp::Logger getLogger ()
 
- Protected Attributes inherited from cl_nav2z::CbNav2ZClientBehaviorBase
cl_nav2z::ClNav2ZmoveBaseClient_
 
rclcpp_action::ResultCode navigationResult_
 

Detailed Description

Definition at line 32 of file cb_navigate_backwards.hpp.

Constructor & Destructor Documentation

◆ CbNavigateBackwards()

cl_nav2z::CbNavigateBackwards::CbNavigateBackwards ( float  backwardDistance)

Definition at line 35 of file cb_navigate_backward.cpp.

36{
37 if (backwardDistance < 0)
38 {
39 RCLCPP_ERROR(getLogger(), "[CbNavigateBackwards] distance must be greater or equal than 0");
40 this->backwardDistance = 0;
41 }
43}

References backwardDistance, and smacc2::ISmaccClientBehavior::getLogger().

Here is the call graph for this function:

Member Function Documentation

◆ onEntry()

void cl_nav2z::CbNavigateBackwards::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 45 of file cb_navigate_backward.cpp.

46{
47 // straight motion distance
48 double dist = backwardDistance;
49
50 RCLCPP_INFO_STREAM(
51 getLogger(), "[CbNavigateBackwards] Straight backwards motion distance: " << dist);
52
54 auto referenceFrame = p->getReferenceFrame();
55 auto currentPoseMsg = p->toPoseMsg();
56 tf2::Transform currentPose;
57 tf2::fromMsg(currentPoseMsg, currentPose);
58
59 tf2::Transform backwardDeltaTransform;
60 backwardDeltaTransform.setIdentity();
61 backwardDeltaTransform.setOrigin(tf2::Vector3(-dist, 0, 0));
62
63 tf2::Transform targetPose = currentPose * backwardDeltaTransform;
64
65 ClNav2Z::Goal goal;
66 goal.pose.header.frame_id = referenceFrame;
67 goal.pose.header.stamp = getNode()->now();
68 tf2::toMsg(targetPose, goal.pose.pose);
69 RCLCPP_INFO_STREAM(getLogger(), "[CbNavigateBackwards] TARGET POSE BACKWARDS: " << goal.pose);
70
71 geometry_msgs::msg::PoseStamped currentStampedPoseMsg;
72 currentStampedPoseMsg.header.frame_id = referenceFrame;
73 currentStampedPoseMsg.header.stamp = getNode()->now();
74 tf2::toMsg(currentPose, currentStampedPoseMsg.pose);
75
77 if (odomTracker_ != nullptr)
78 {
79 this->odomTracker_->clearPath();
80 this->odomTracker_->setStartPoint(currentStampedPoseMsg);
81 this->odomTracker_->setWorkingMode(WorkingMode::RECORD_PATH);
82 }
83
84 auto plannerSwitcher = moveBaseClient_->getComponent<PlannerSwitcher>();
85 plannerSwitcher->setBackwardPlanner();
86
87 auto goalCheckerSwitcher = moveBaseClient_->getComponent<GoalCheckerSwitcher>();
88 goalCheckerSwitcher->setGoalCheckerId("backward_goal_checker");
89
91}
cl_nav2z::odom_tracker::OdomTracker * odomTracker_
const std::string & getReferenceFrame() const
Definition: cp_pose.hpp:77
void setWorkingMode(WorkingMode workingMode)
void setStartPoint(const geometry_msgs::msg::PoseStamped &pose)
virtual rclcpp::Node::SharedPtr getNode()
TComponent * getComponent()
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal)

References backwardDistance, cl_nav2z::odom_tracker::OdomTracker::clearPath(), smacc2::ISmaccClient::getComponent(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getNode(), cl_nav2z::Pose::getReferenceFrame(), cl_nav2z::CbNav2ZClientBehaviorBase::moveBaseClient_, odomTracker_, smacc2::client_bases::SmaccActionClientBase< ActionType >::sendGoal(), cl_nav2z::PlannerSwitcher::setBackwardPlanner(), cl_nav2z::GoalCheckerSwitcher::setGoalCheckerId(), cl_nav2z::odom_tracker::OdomTracker::setStartPoint(), and cl_nav2z::odom_tracker::OdomTracker::setWorkingMode().

Here is the call graph for this function:

◆ onExit()

void cl_nav2z::CbNavigateBackwards::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 93 of file cb_navigate_backward.cpp.

94{
95 if (odomTracker_)
96 {
97 this->odomTracker_->setWorkingMode(WorkingMode::IDLE);
98 }
99}

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

Here is the call graph for this function:

Member Data Documentation

◆ backwardDistance

float cl_nav2z::CbNavigateBackwards::backwardDistance

Definition at line 35 of file cb_navigate_backwards.hpp.

Referenced by CbNavigateBackwards(), and onEntry().

◆ backwardSpeed

std::optional<float> cl_nav2z::CbNavigateBackwards::backwardSpeed

Definition at line 38 of file cb_navigate_backwards.hpp.

◆ goalChecker_

std::optional<std::string> cl_nav2z::CbNavigateBackwards::goalChecker_

Definition at line 40 of file cb_navigate_backwards.hpp.

◆ odomTracker_

cl_nav2z::odom_tracker::OdomTracker* cl_nav2z::CbNavigateBackwards::odomTracker_

Definition at line 42 of file cb_navigate_backwards.hpp.

Referenced by onEntry(), and onExit().


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