SMACC2
|
#include <cb_navigate_forward.hpp>
Public Attributes | |
CbNavigateForwardOptions | options |
Protected Attributes | |
odom_tracker::CpOdomTracker * | odomTracker_ |
std::optional< geometry_msgs::msg::PoseStamped > | goalPose_ |
std::optional< float > | forwardDistance_ |
Protected Attributes inherited from cl_nitrosz::CbNav2ZClientBehaviorBase | |
cl_nitrosz::ClNitrosZ * | nitroszClient_ |
cl_nitrosz::ClNitrosZ::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_nitrosz::CbNav2ZClientBehaviorBase | |
void | sendGoal (ClNitrosZ::Goal &goal) |
void | cancelGoal () |
bool | isOwnActionResponse (const ClNitrosZ::WrappedResult &) |
virtual void | onNavigationResult (const ClNitrosZ::WrappedResult &) |
virtual void | onNavigationActionSuccess (const ClNitrosZ::WrappedResult &) |
virtual void | onNavigationActionAbort (const ClNitrosZ::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 () |
ISmaccState * | getCurrentState () |
virtual rclcpp::Node::SharedPtr | getNode () const |
virtual rclcpp::Logger | getLogger () const |
Definition at line 48 of file cb_navigate_forward.hpp.
cl_nitrosz::CbNavigateForward::CbNavigateForward | ( | ) |
Definition at line 36 of file cb_navigate_forward.cpp.
cl_nitrosz::CbNavigateForward::CbNavigateForward | ( | float | forwardDistance | ) |
Definition at line 35 of file cb_navigate_forward.cpp.
cl_nitrosz::CbNavigateForward::CbNavigateForward | ( | geometry_msgs::msg::PoseStamped | goalPosition | ) |
Definition at line 38 of file cb_navigate_forward.cpp.
|
virtual |
Definition at line 40 of file cb_navigate_forward.cpp.
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 57 of file cb_navigate_forward.cpp.
References cl_nitrosz::CbNavigateForwardOptions::forceInitialOrientation, forwardDistance_, smacc2::ISmaccClient::getComponent(), smacc2::ISmaccClientBehavior::getCurrentState(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccState::getName(), smacc2::ISmaccClientBehavior::getNode(), cl_nitrosz::Pose::getReferenceFrame(), goalPose_, cl_nitrosz::CbNav2ZClientBehaviorBase::nitroszClient_, odomTracker_, options, cl_nitrosz::odom_tracker::CpOdomTracker::pushPath(), cl_nitrosz::CbNav2ZClientBehaviorBase::sendGoal(), cl_nitrosz::odom_tracker::CpOdomTracker::setCurrentMotionGoal(), setForwardDistance(), cl_nitrosz::CpPlannerSwitcher::setForwardPlanner(), cl_nitrosz::CpGoalCheckerSwitcher::setGoalCheckerId(), cl_nitrosz::odom_tracker::CpOdomTracker::setStartPoint(), and cl_nitrosz::odom_tracker::CpOdomTracker::setWorkingMode().
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 150 of file cb_navigate_forward.cpp.
References odomTracker_, and cl_nitrosz::odom_tracker::CpOdomTracker::setWorkingMode().
void cl_nitrosz::CbNavigateForward::setForwardDistance | ( | float | distance_meters | ) |
Definition at line 42 of file cb_navigate_forward.cpp.
References forwardDistance_, smacc2::ISmaccClientBehavior::getLogger(), and smacc2::ISmaccClientBehavior::getName().
Referenced by onEntry().
|
protected |
Definition at line 77 of file cb_navigate_forward.hpp.
Referenced by onEntry(), and setForwardDistance().
|
protected |
Definition at line 75 of file cb_navigate_forward.hpp.
Referenced by onEntry().
|
protected |
Definition at line 73 of file cb_navigate_forward.hpp.
CbNavigateForwardOptions cl_nitrosz::CbNavigateForward::options |
Definition at line 51 of file cb_navigate_forward.hpp.
Referenced by onEntry().