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

#include <cb_navigate_global_position.hpp>

Inheritance diagram for cl_nav2z::CbNavigateGlobalPosition:
Inheritance graph
Collaboration diagram for cl_nav2z::CbNavigateGlobalPosition:
Collaboration graph

Public Member Functions

 CbNavigateGlobalPosition ()
 
 CbNavigateGlobalPosition (float x, float y, float yaw)
 
void setGoal (const geometry_msgs::msg::Pose &pose)
 
virtual void onEntry () override
 
void onExit () override
 
void execute ()
 
- 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

geometry_msgs::msg::Point goalPosition
 
float goalYaw
 
std::optional< float > yawTolerance
 
std::optional< float > yawToleranceX
 
std::optional< float > yawToleranceY
 
std::optional< std::string > goalChecker_
 

Private Member Functions

void readStartPoseFromParameterServer (ClNav2Z::Goal &goal)
 

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 29 of file cb_navigate_global_position.hpp.

Constructor & Destructor Documentation

◆ CbNavigateGlobalPosition() [1/2]

cl_nav2z::CbNavigateGlobalPosition::CbNavigateGlobalPosition ( )

◆ CbNavigateGlobalPosition() [2/2]

cl_nav2z::CbNavigateGlobalPosition::CbNavigateGlobalPosition ( float  x,
float  y,
float  yaw 
)

Definition at line 32 of file cb_navigate_global_position.cpp.

33{
34 auto p = geometry_msgs::msg::Point();
35 p.x = x;
36 p.y = y;
37 goalPosition = p;
38 goalYaw = yaw;
39}

References goalPosition, and goalYaw.

Member Function Documentation

◆ execute()

void cl_nav2z::CbNavigateGlobalPosition::execute ( )

Definition at line 70 of file cb_navigate_global_position.cpp.

71{
73 auto referenceFrame = p->getReferenceFrame();
74 // auto currentPoseMsg = p->toPoseMsg();
75
76 RCLCPP_INFO(getLogger(), "Sending Goal to MoveBase");
77 ClNav2Z::Goal goal;
78 goal.pose.header.frame_id = referenceFrame;
79 goal.pose.header.stamp = getNode()->now();
80
81 goal.pose.pose.position = goalPosition;
82 tf2::Quaternion q;
83 q.setRPY(0, 0, goalYaw);
84 goal.pose.pose.orientation = tf2::toMsg(q);
85 // store the start pose on the state machine storage so that it can
86 // be referenced from other states (for example return to radial start)
87 this->getStateMachine()->setGlobalSMData("radial_start_pose", goal.pose);
88
90}
const std::string & getReferenceFrame() const
Definition: cp_pose.hpp:77
virtual rclcpp::Node::SharedPtr getNode()
TComponent * getComponent()
void setGlobalSMData(std::string name, T value)
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal)

References smacc2::ISmaccClient::getComponent(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getNode(), cl_nav2z::Pose::getReferenceFrame(), smacc2::ISmaccClientBehavior::getStateMachine(), goalPosition, goalYaw, cl_nav2z::CbNav2ZClientBehaviorBase::moveBaseClient_, smacc2::client_bases::SmaccActionClientBase< ActionType >::sendGoal(), and smacc2::ISmaccStateMachine::setGlobalSMData().

Referenced by onEntry().

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

◆ onEntry()

void cl_nav2z::CbNavigateGlobalPosition::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 47 of file cb_navigate_global_position.cpp.

48{
49 RCLCPP_INFO(getLogger(), "Entering Navigate Global position");
50 RCLCPP_INFO(getLogger(), "Component requirements completed");
51
52 auto pose = moveBaseClient_->getComponent<cl_nav2z::Pose>()->toPoseMsg();
53 auto * odomTracker = moveBaseClient_->getComponent<OdomTracker>();
54
55 auto plannerSwitcher = moveBaseClient_->getComponent<PlannerSwitcher>();
56 plannerSwitcher->setDefaultPlanners();
57
58 auto goalCheckerSwitcher = moveBaseClient_->getComponent<GoalCheckerSwitcher>();
59 goalCheckerSwitcher->setGoalCheckerId("goal_checker");
60
61 auto pathname = this->getCurrentState()->getName() + " - " + getName();
62 odomTracker->pushPath(pathname);
63 odomTracker->setStartPoint(pose);
64 odomTracker->setWorkingMode(WorkingMode::RECORD_PATH);
65
66 execute();
67}
virtual std::string getName()=0

References execute(), smacc2::ISmaccClient::getComponent(), smacc2::ISmaccClientBehavior::getCurrentState(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccState::getName(), cl_nav2z::CbNav2ZClientBehaviorBase::moveBaseClient_, and cl_nav2z::GoalCheckerSwitcher::setGoalCheckerId().

Here is the call graph for this function:

◆ onExit()

void cl_nav2z::CbNavigateGlobalPosition::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 94 of file cb_navigate_global_position.cpp.

95{
96 RCLCPP_INFO(getLogger(), "Exiting move goal Action Client");
97}

References smacc2::ISmaccClientBehavior::getLogger().

Here is the call graph for this function:

◆ readStartPoseFromParameterServer()

void cl_nav2z::CbNavigateGlobalPosition::readStartPoseFromParameterServer ( ClNav2Z::Goal goal)
private

◆ setGoal()

void cl_nav2z::CbNavigateGlobalPosition::setGoal ( const geometry_msgs::msg::Pose &  pose)

Definition at line 41 of file cb_navigate_global_position.cpp.

42{
43 goalPosition = pose.position;
44 goalYaw = tf2::getYaw(pose.orientation);
45}

References goalPosition, and goalYaw.

Member Data Documentation

◆ goalChecker_

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

Definition at line 39 of file cb_navigate_global_position.hpp.

◆ goalPosition

geometry_msgs::msg::Point cl_nav2z::CbNavigateGlobalPosition::goalPosition

Definition at line 32 of file cb_navigate_global_position.hpp.

Referenced by CbNavigateGlobalPosition(), execute(), and setGoal().

◆ goalYaw

float cl_nav2z::CbNavigateGlobalPosition::goalYaw

Definition at line 33 of file cb_navigate_global_position.hpp.

Referenced by CbNavigateGlobalPosition(), execute(), and setGoal().

◆ yawTolerance

std::optional<float> cl_nav2z::CbNavigateGlobalPosition::yawTolerance

Definition at line 35 of file cb_navigate_global_position.hpp.

◆ yawToleranceX

std::optional<float> cl_nav2z::CbNavigateGlobalPosition::yawToleranceX

Definition at line 36 of file cb_navigate_global_position.hpp.

◆ yawToleranceY

std::optional<float> cl_nav2z::CbNavigateGlobalPosition::yawToleranceY

Definition at line 37 of file cb_navigate_global_position.hpp.


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