|
SMACC2
|
#include <cb_position_control_free_space.hpp>


Public Member Functions | |
| CbPositionControlFreeSpace () | |
| void | updateParameters () |
| void | onEntry () override |
| void | onExit () override |
| CbPositionControlFreeSpace () | |
| void | updateParameters () |
| void | onEntry () override |
| void | onExit () override |
Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior | |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onOrthogonalAllocation () |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onStateOrthogonalAllocation () |
| 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 () |
| ISmaccStateMachine * | getStateMachine () |
| std::string | getName () const |
| template<typename SmaccClientType > | |
| void | requiresClient (SmaccClientType *&storage) |
| template<typename SmaccComponentType > | |
| void | requiresComponent (SmaccComponentType *&storage, bool throwExceptionIfNotExist) |
| template<typename SmaccComponentType > | |
| void | requiresComponent (SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT) |
Public Attributes | |
| double | yaw_goal_tolerance_rads_ = 0.1 |
| double | threshold_distance_ = 3.0 |
| geometry_msgs::msg::Pose | target_pose_ |
Private Attributes | |
| double | targetYaw_ |
| bool | goalReached_ |
| double | k_betta_ |
| double | max_angular_yaw_speed_ |
| double | prev_error_linear_ = 0.0 |
| double | prev_error_angular_ = 0.0 |
| double | integral_linear_ = 0.0 |
| double | integral_angular_ = 0.0 |
| double | max_linear_velocity = 1.0 |
| double | max_angular_velocity = 1.0 |
| rclcpp::Publisher< geometry_msgs::msg::Twist >::SharedPtr | cmd_vel_pub_ |
Additional Inherited Members | |
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 29 of file cb_position_control_free_space.hpp.
| cl_nav2z::CbPositionControlFreeSpace::CbPositionControlFreeSpace | ( | ) |
Definition at line 31 of file cb_position_control_free_space.cpp.
| cl_nav2z::CbPositionControlFreeSpace::CbPositionControlFreeSpace | ( | ) |
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 38 of file cb_position_control_free_space.cpp.
References cmd_vel_pub_, smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccClientBehavior::getNode(), goalReached_, integral_angular_, integral_linear_, max_angular_velocity, max_linear_velocity, smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), prev_error_angular_, prev_error_linear_, smacc2::ISmaccClientBehavior::requiresComponent(), target_pose_, and threshold_distance_.
Referenced by cl_nav2z::CbNavigateNextWaypointFree::onEntry().


|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 198 of file cb_position_control_free_space.cpp.
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
| void cl_nav2z::CbPositionControlFreeSpace::updateParameters | ( | ) |
Definition at line 36 of file cb_position_control_free_space.cpp.
| void cl_nav2z::CbPositionControlFreeSpace::updateParameters | ( | ) |
|
private |
Definition at line 47 of file cb_position_control_free_space.hpp.
Referenced by onEntry().
|
private |
Definition at line 33 of file cb_position_control_free_space.hpp.
Referenced by onEntry().
|
private |
Definition at line 40 of file cb_position_control_free_space.hpp.
Referenced by onEntry().
|
private |
Definition at line 39 of file cb_position_control_free_space.hpp.
Referenced by onEntry().
|
private |
Definition at line 34 of file cb_position_control_free_space.hpp.
|
private |
Definition at line 45 of file cb_position_control_free_space.hpp.
Referenced by onEntry().
|
private |
Definition at line 35 of file cb_position_control_free_space.hpp.
|
private |
Definition at line 44 of file cb_position_control_free_space.hpp.
Referenced by onEntry().
|
private |
Definition at line 38 of file cb_position_control_free_space.hpp.
Referenced by onEntry().
|
private |
Definition at line 37 of file cb_position_control_free_space.hpp.
Referenced by onEntry().
| geometry_msgs::msg::Pose cl_nav2z::CbPositionControlFreeSpace::target_pose_ |
Definition at line 54 of file cb_position_control_free_space.hpp.
Referenced by cl_nav2z::CbNavigateNextWaypointFree::onEntry(), and onEntry().
|
private |
Definition at line 32 of file cb_position_control_free_space.hpp.
| double cl_nav2z::CbPositionControlFreeSpace::threshold_distance_ = 3.0 |
Definition at line 52 of file cb_position_control_free_space.hpp.
Referenced by onEntry().
| double cl_nav2z::CbPositionControlFreeSpace::yaw_goal_tolerance_rads_ = 0.1 |
Definition at line 50 of file cb_position_control_free_space.hpp.