SMACC2
Public Member Functions | Private Attributes | List of all members
sm_autoware_avp::clients::autoware_client::CbSetupInitialPoseEstimation Class Reference

#include <cb_setup_initial_pose_estimation.hpp>

Inheritance diagram for sm_autoware_avp::clients::autoware_client::CbSetupInitialPoseEstimation:
Inheritance graph
Collaboration diagram for sm_autoware_avp::clients::autoware_client::CbSetupInitialPoseEstimation:
Collaboration graph

Public Member Functions

 CbSetupInitialPoseEstimation (const geometry_msgs::msg::PoseWithCovarianceStamped &initialStatePose)
 
virtual void onEntry () override
 
void onExit () override
 
- 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)
 

Private Attributes

geometry_msgs::msg::PoseWithCovarianceStamped initialStatePose_
 

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 ()
 

Detailed Description

Definition at line 31 of file cb_setup_initial_pose_estimation.hpp.

Constructor & Destructor Documentation

◆ CbSetupInitialPoseEstimation()

sm_autoware_avp::clients::autoware_client::CbSetupInitialPoseEstimation::CbSetupInitialPoseEstimation ( const geometry_msgs::msg::PoseWithCovarianceStamped &  initialStatePose)

Definition at line 30 of file cb_setup_initial_pose_estimation.cpp.

32: initialStatePose_(initialStatePose)
33{
34}

Member Function Documentation

◆ onEntry()

void sm_autoware_avp::clients::autoware_client::CbSetupInitialPoseEstimation::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 36 of file cb_setup_initial_pose_estimation.cpp.

37{
39 initialStatePose_.header.stamp = getNode()->now();
40 initialStatePose_.header.frame_id = "map";
41
42 this->requiresClient(autowareClient_);
43
45}
void publishInitialPoseEstimation(const geometry_msgs::msg::PoseWithCovarianceStamped &msg)
virtual rclcpp::Node::SharedPtr getNode()
void requiresClient(SmaccClientType *&storage)

References smacc2::ISmaccClientBehavior::getNode(), initialStatePose_, sm_autoware_avp::clients::ClAutoware::publishInitialPoseEstimation(), and smacc2::ISmaccClientBehavior::requiresClient().

Here is the call graph for this function:

◆ onExit()

void sm_autoware_avp::clients::autoware_client::CbSetupInitialPoseEstimation::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 47 of file cb_setup_initial_pose_estimation.cpp.

47{}

Member Data Documentation

◆ initialStatePose_

geometry_msgs::msg::PoseWithCovarianceStamped sm_autoware_avp::clients::autoware_client::CbSetupInitialPoseEstimation::initialStatePose_
private

Definition at line 41 of file cb_setup_initial_pose_estimation.hpp.

Referenced by onEntry().


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