SMACC2
|
#include <cb_absolute_rotate.hpp>
Public Attributes | |
std::shared_ptr< tf2_ros::Buffer > | listener |
float | absoluteGoalAngleDegree |
std::optional< float > | yawGoalTolerance |
std::optional< float > | maxVelTheta |
std::optional< SpinningPlanner > | spinningPlanner |
Private Member Functions | |
void | updateTemporalBehaviorParameters (bool undo) |
Private Attributes | |
float | oldYawTolerance |
float | oldMaxVelTheta |
float | oldMinVelTheta |
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 |
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_ |
Definition at line 29 of file cb_absolute_rotate.hpp.
cl_nitrosz::CbAbsoluteRotate::CbAbsoluteRotate | ( | ) |
Definition at line 32 of file cb_absolute_rotate.cpp.
cl_nitrosz::CbAbsoluteRotate::CbAbsoluteRotate | ( | float | absoluteGoalAngleDegree, |
float | yawGoalTolerance = -1 |
||
) |
Definition at line 33 of file cb_absolute_rotate.cpp.
References absoluteGoalAngleDegree, and yawGoalTolerance.
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Reimplemented in cl_nitrosz::CbRotateLookAt.
Definition at line 43 of file cb_absolute_rotate.cpp.
References absoluteGoalAngleDegree, smacc2::ISmaccClient::getComponent(), smacc2::ISmaccClientBehavior::getCurrentState(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccState::getName(), smacc2::ISmaccClientBehavior::getNode(), cl_nitrosz::Pose::getReferenceFrame(), listener, cl_nitrosz::CbNav2ZClientBehaviorBase::nitroszClient_, cl_nitrosz::PureSpinning, cl_nitrosz::odom_tracker::RECORD_PATH, cl_nitrosz::CbNav2ZClientBehaviorBase::sendGoal(), cl_nitrosz::CpGoalCheckerSwitcher::setGoalCheckerId(), cl_nitrosz::CpPlannerSwitcher::setPureSpinningPlanner(), spinningPlanner, and updateTemporalBehaviorParameters().
Referenced by cl_nitrosz::CbRotateLookAt::onEntry().
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 258 of file cb_absolute_rotate.cpp.
References cl_nitrosz::PureSpinning, spinningPlanner, and updateTemporalBehaviorParameters().
|
private |
Definition at line 101 of file cb_absolute_rotate.cpp.
References cl_nitrosz::Default, smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccClientBehavior::getNode(), maxVelTheta, oldMaxVelTheta, oldMinVelTheta, oldYawTolerance, cl_nitrosz::PureSpinning, spinningPlanner, and yawGoalTolerance.
Referenced by onEntry(), and onExit().
float cl_nitrosz::CbAbsoluteRotate::absoluteGoalAngleDegree |
Definition at line 34 of file cb_absolute_rotate.hpp.
Referenced by CbAbsoluteRotate(), onEntry(), and cl_nitrosz::CbRotateLookAt::onEntry().
std::shared_ptr<tf2_ros::Buffer> cl_nitrosz::CbAbsoluteRotate::listener |
Definition at line 32 of file cb_absolute_rotate.hpp.
Referenced by onEntry().
std::optional<float> cl_nitrosz::CbAbsoluteRotate::maxVelTheta |
Definition at line 36 of file cb_absolute_rotate.hpp.
Referenced by updateTemporalBehaviorParameters().
|
private |
Definition at line 48 of file cb_absolute_rotate.hpp.
Referenced by updateTemporalBehaviorParameters().
|
private |
Definition at line 49 of file cb_absolute_rotate.hpp.
Referenced by updateTemporalBehaviorParameters().
|
private |
Definition at line 47 of file cb_absolute_rotate.hpp.
Referenced by updateTemporalBehaviorParameters().
std::optional<SpinningPlanner> cl_nitrosz::CbAbsoluteRotate::spinningPlanner |
Definition at line 37 of file cb_absolute_rotate.hpp.
Referenced by onEntry(), onExit(), and updateTemporalBehaviorParameters().
std::optional<float> cl_nitrosz::CbAbsoluteRotate::yawGoalTolerance |
Definition at line 35 of file cb_absolute_rotate.hpp.
Referenced by CbAbsoluteRotate(), and updateTemporalBehaviorParameters().