Class ControllerAction

Inheritance Relationships

Base Type

Class Documentation

class ControllerAction : public mbf_abstract_nav::AbstractActionBase<mbf_msgs::action::ExePath, AbstractControllerExecution>

Public Types

typedef std::shared_ptr<ControllerAction> Ptr

Public Functions

ControllerAction(const rclcpp::Node::SharedPtr &node, const std::string &name, const mbf_utility::RobotInformation::ConstPtr &robot_info)
void start(GoalHandlePtr goal_handle, typename AbstractControllerExecution::Ptr execution_ptr)

Start controller action. Override abstract action version to allow updating current plan without stopping execution.

Parameters:
  • goal_handle – Pointer to the goal handle received on action execution callback.

  • execution_ptr – Pointer to the execution descriptor.

virtual void runImpl(const GoalHandlePtr &goal_handle, AbstractControllerExecution &execution) override

Protected Functions

void publishExePathFeedback(GoalHandle &goal_handle, uint32_t outcome, const std::string &message, const geometry_msgs::msg::TwistStamped &current_twist)
void fillExePathResult(uint32_t outcome, const std::string &message, mbf_msgs::action::ExePath::Result &result)

Utility method to fill the ExePath action result in a single line.

Parameters:
  • outcome – ExePath action outcome

  • message – ExePath action message

  • result – The action result to fill

Protected Attributes

std::mutex goal_mtx_

lock goal handle for updating it while running

geometry_msgs::msg::PoseStamped robot_pose_

Current robot pose.

geometry_msgs::msg::PoseStamped goal_pose_

Current goal pose.