Skip to content

Commit

Permalink
Rafal's suggestions applied
Browse files Browse the repository at this point in the history
Signed-off-by: Jakub Delicat <[email protected]>
  • Loading branch information
delihus committed Nov 15, 2024
1 parent 7605e89 commit 0a84793
Show file tree
Hide file tree
Showing 6 changed files with 18 additions and 18 deletions.
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -109,6 +109,7 @@ Launch arguments are largely common to both simulation and physical robot. Howev
| 🤖🖥️ | `use_ekf` | Enable or disable EKF. <br/> ***bool:*** `True` |
| 🤖🖥️ | `use_sim` | Whether simulation is used. <br/> ***bool:*** `False` |
| 🤖🖥️ | `user_led_animations_file` | Path to a YAML file with a description of the user-defined animations. <br/> ***string:*** `''` |
| 🤖🖥️ | `panther_charging_dock.use_wibotic_info` | Use readings from `wibotic_info` topics to ensure that a robot is charging. <br/> **bool**: `True` |
| 🤖🖥️ | `wheel_config_path` | Path to wheel configuration file. <br/> ***string:*** [`{wheel_type}.yaml`](./panther_description/config) |
| 🤖🖥️ | `wheel_type` | Type of wheel. If you choose a value from the preset options ('WH01', 'WH02', 'WH04'), you can ignore the 'wheel_config_path' and 'controller_config_path' parameters. For custom wheels, please define these parameters to point to files that accurately describe the custom wheels. <br/> ***string:*** `WH01` (choices: `WH01`, `WH02`, `WH04`, `custom`) |
| 🖥️ | `x` | Initial robot position in the global 'x' axis. <br/> ***float:*** `0.0` |
Expand Down
14 changes: 7 additions & 7 deletions panther_docking/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -46,10 +46,10 @@ The package contains a `PantherChargingDock` plugin for the [opennav_docking](ht

- `base_frame` [*string*, default: **base_link**]: A base frame id of a robot.
- `fixed_frame` [*string*, default: **odom**]: A fixed frame id of a robot.
- `<dock_type>.external_detection_timeout` [*double*, default: **0.2**]: A timeout in seconds for looking up a transformation from an april tag of a dock to a base frame id.
- `<dock_type>.docking_distance_threshold` [*double*, default: **0.05**]: A threshold of a distance between a robot pose and a dock pose to declare if docking succeed.
- `<dock_type>.docking_yaw_threshold` [*double*, default: **0.3**]: A threshold of a difference of yaw angles between a robot pose and a dock pose to declare if docking succeed.
- `<dock_type>.staging_x_offset` [*double*, default: **-0.7**]: A staging pose is defined by offsetting a dock pose in axis X.
- `<dock_type>.filter_coef` [*double*, default: **0.1**]: A key parameter that influences the trade-off between the filter's responsiveness and its smoothness, balancing how quickly it reacts to new pose data pose how much it smooths out fluctuations.
- `<dock_type>.use_wibotic_info` [*bool*, default: **True**]: Use readings from `wibotic_info` topics to ensure that a robot is charging.
- `<dock_type>.wibotic_info_timeout` [*double*, default: **0.2**]: A timeout in seconds for wibotic_info.
- `panther_charging_dock.external_detection_timeout` [*double*, default: **0.2**]: A timeout in seconds for looking up a transformation from an april tag of a dock to a base frame id.
- `panther_charging_dock.docking_distance_threshold` [*double*, default: **0.05**]: A threshold of a distance between a robot pose and a dock pose to declare if docking succeed.
- `panther_charging_dock.docking_yaw_threshold` [*double*, default: **0.3**]: A threshold of a difference of yaw angles between a robot pose and a dock pose to declare if docking succeed.
- `panther_charging_dock.staging_x_offset` [*double*, default: **-0.7**]: A staging pose is defined by offsetting a dock pose in axis X.
- `panther_charging_dock.filter_coef` [*double*, default: **0.1**]: A key parameter that influences the trade-off between the filter's responsiveness and its smoothness, balancing how quickly it reacts to new pose data pose how much it smooths out fluctuations.
- `panther_charging_dock.use_wibotic_info` [*bool*, default: **True**]: Use readings from `wibotic_info` topics to ensure that a robot is charging.
- `panther_charging_dock.wibotic_info_timeout` [*double*, default: **1.5**]: A timeout in seconds to receive wibotic_info.
Original file line number Diff line number Diff line change
Expand Up @@ -155,16 +155,14 @@ class PantherChargingDock : public opennav_docking_core::ChargingDock
/**
* @brief Set the dock pose.
*
* This method sets the dock pose. It can be used as a callback for a subscription.
* This method sets the dock pose. It can be used as a callback for a subscription.
*
* @param pose The dock pose.
*/
void setDockPose(const PoseStampedMsg::SharedPtr pose);

/**
* @brief Set the Wibotic info.
*
* This method sets the Wibotic info. It can be used as a callback for a subscription.
* @brief Wibotic info callback, used when `use_wibotic_info` is enabled.
*
* @param msg The Wibotic info message.
*/
Expand Down
10 changes: 6 additions & 4 deletions panther_docking/launch/docking.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -151,14 +151,16 @@ def generate_launch_description():
name="docking_manager",
parameters=[
PathJoinSubstitution([panther_manager_dir, "config", "docking_manager.yaml"]),
{"bt_project_path": PathJoinSubstitution(
[panther_manager_dir, "behavior_trees", "DockingBT.btproj"])},
{
"bt_project_path": PathJoinSubstitution(
[panther_manager_dir, "behavior_trees", "DockingBT.btproj"]
)
},
],
namespace=namespace,
emulate_tty=True,
)


return LaunchDescription(
[
declare_use_docking_arg,
Expand All @@ -170,6 +172,6 @@ def generate_launch_description():
docking_server_activate_node,
dock_pose_publisher,
wibotic_connector_can,
docking_manager_node
docking_manager_node,
]
)
2 changes: 1 addition & 1 deletion panther_docking/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
<depend>geometry_msgs</depend>
<depend>nav2_util</depend>
<depend>opennav_docking</depend>
<depend>panther_manager</depend>
<depend>panther_utils</depend>
<depend>pluginlib</depend>
<depend>python3-pip</depend>
Expand All @@ -28,7 +29,6 @@
<depend>wibotic_msgs</depend>

<!-- FIXME: Remove before release -->
<depend >panther_manager</depend>

<exec_depend>nav2_lifecycle_manager</exec_depend>
<exec_depend>python3-imageio</exec_depend>
Expand Down
3 changes: 1 addition & 2 deletions panther_docking/src/panther_charging_dock.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,11 +45,10 @@ void PantherChargingDock::configure(
declareParameters(node);
getParameters(node);

if(!use_wibotic_info_){
if (!use_wibotic_info_) {
RCLCPP_INFO(logger_, "Wibotic info is disabled.");
}


pose_filter_ = std::make_unique<opennav_docking::PoseFilter>(
pose_filter_coef_, external_detection_timeout_);
}
Expand Down

0 comments on commit 0a84793

Please sign in to comment.