Class SimpleChargingDock

Inheritance Relationships

Base Type

  • public opennav_docking_core::ChargingDock

Class Documentation

class SimpleChargingDock : public opennav_docking_core::ChargingDock

Public Functions

inline SimpleChargingDock()

Constructor.

virtual void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &name, std::shared_ptr<tf2_ros::Buffer> tf)
Parameters:
  • parent – pointer to user’s node

  • name – The name of this planner

  • tfA pointer to a TF buffer

inline virtual void cleanup()

Method to cleanup resources used on shutdown.

inline virtual void activate()

Method to active Behavior and any threads involved in execution.

inline virtual void deactivate()

Method to deactive Behavior and any threads involved in execution.

virtual geometry_msgs::msg::PoseStamped getStagingPose(const geometry_msgs::msg::Pose &pose, const std::string &frame)

Method to obtain the dock’s staging pose. This method should likely be using TF and the dock’s pose information to find the staging pose from a static or parameterized staging pose relative to the docking pose.

Parameters:
  • poseDock with pose

  • frameDock’s frame of pose

Returns:

PoseStamped of staging pose in the specified frame

virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped &pose)

Method to obtain the refined pose of the dock, usually based on sensors.

Parameters:
  • pose – The initial estimate of the dock pose.

  • frame – The frame of the initial estimate.

virtual bool isDocked()
virtual bool isCharging()
virtual bool disableCharging()
virtual bool hasStoppedCharging()

Similar to isCharging() but called when undocking.

Protected Functions

void jointStateCallback(const sensor_msgs::msg::JointState::SharedPtr state)

Protected Attributes

rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_sub_
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_pub_
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr filtered_dock_pose_pub_
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr staging_pose_pub_
geometry_msgs::msg::PoseStamped detected_dock_pose_
geometry_msgs::msg::PoseStamped dock_pose_
rclcpp::Subscription<sensor_msgs::msg::BatteryState>::SharedPtr battery_sub_
bool is_charging_
bool use_battery_status_
rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr joint_state_sub_
std::vector<std::string> stall_joint_names_
double stall_velocity_threshold_
double stall_effort_threshold_
bool is_stalled_
bool use_external_detection_pose_
double external_detection_timeout_
tf2::Quaternion external_detection_rotation_
double external_detection_translation_x_
double external_detection_translation_y_
std::shared_ptr<PoseFilter> filter_
double charging_threshold_
double docking_threshold_
double staging_x_offset_
double staging_yaw_offset_
rclcpp_lifecycle::LifecycleNode::SharedPtr node_
std::shared_ptr<tf2_ros::Buffer> tf2_buffer_