Class ClAutoware
Defined in File cl_autoware.hpp
Inheritance Relationships
Base Type
public smacc2::ISmaccClient
Class Documentation
-
class ClAutoware : public smacc2::ISmaccClient
Public Functions
-
template<typename TOrthogonal, typename TSourceObject>
inline void onOrthogonalAllocation()
-
inline void onInitialize() override
-
inline bool checkGoalReached()
-
inline void onNdtPoseReceived(const geometry_msgs::msg::PoseWithCovarianceStamped &msg)
-
inline void publishGoalPose(const geometry_msgs::msg::PoseStamped &msg)
-
inline void publishInitialPoseEstimation(const geometry_msgs::msg::PoseWithCovarianceStamped &msg)
Public Members
-
smacc2::components::CpTopicPublisher<geometry_msgs::msg::PoseWithCovarianceStamped> *cppubLocation_
-
smacc2::components::CpTopicPublisher<geometry_msgs::msg::PoseStamped> *cpppubGoalPose_
-
std::optional<geometry_msgs::msg::PoseWithCovarianceStamped> lastPose_
-
std::optional<geometry_msgs::msg::PoseStamped> lastGoal_
-
double goalToleranceMeters_ = 3.5
-
std::function<void(const geometry_msgs::msg::PoseWithCovarianceStamped&)> postEvAutoLocalized_
-
std::function<void()> postEvGoalReached_
-
template<typename TOrthogonal, typename TSourceObject>