Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Jan 14, 2025
1 parent aef1abf commit 1202d17
Show file tree
Hide file tree
Showing 4 changed files with 18 additions and 17 deletions.
28 changes: 14 additions & 14 deletions sensing/autoware_gnss_poser/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -17,29 +17,29 @@ If the transformation from `base_link` to the antenna cannot be obtained, it out

| Name | Type | Description |
| ------------------------------ | ------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------ |
| `/map/map_projector_info` | `autoware_map_msgs::msg::MapProjectorInfo` | map projection info |
| `/map/map_projector_info` | `autoware_map_msgs::msg::MapProjectorInfo` | map projection info |
| `~/input/fix` | `sensor_msgs::msg::NavSatFix` | gnss status message |
| `~/input/autoware_orientation` | `autoware_sensing_msgs::msg::GnssInsOrientationStamped` | orientation [click here for more details](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_sensing_msgs) |

### Output

| Name | Type | Description |
| ------------------------ | ----------------------------------------------- | -------------------------------------------------------------- |
| `~/output/pose` | `geometry_msgs::msg::PoseStamped` | vehicle pose calculated from gnss sensing data |
| `~/output/gnss_pose_cov` | `geometry_msgs::msg::PoseWithCovarianceStamped` | vehicle pose with covariance calculated from gnss sensing data |
| `~/output/gnss_fixed` | `autoware_internal_debug_msgs::msg::BoolStamped` | gnss fix status |
| Name | Type | Description |
| ------------------------ | ------------------------------------------------ | -------------------------------------------------------------- |
| `~/output/pose` | `geometry_msgs::msg::PoseStamped` | vehicle pose calculated from gnss sensing data |
| `~/output/gnss_pose_cov` | `geometry_msgs::msg::PoseWithCovarianceStamped` | vehicle pose with covariance calculated from gnss sensing data |
| `~/output/gnss_fixed` | `autoware_internal_debug_msgs::msg::BoolStamped` | gnss fix status |

## Parameters

Parameters in below table

| Name | Type | Default | Description |
| ------------------------ | -----------------------| ------------------------ | -------------------------------------------------------------- |
| `base_frame` | `string` | `base_link` | frame id for base_frame |
| `gnss_base_frame` | `string` | `gnss_base_link` | frame id for gnss_base_frame |
| `map_frame` | `string` | `map` | frame id for map_frame |
| `use_gnss_ins_orientation` | `boolean` | `true` | use Gnss-Ins orientation |
| `gnss_pose_pub_method` | `integer` | `0` | 0: Instant Value 1: Average Value 2: Median Value. If `buffer_epoch` is set to 0, `gnss_pose_pub_method` loses affect. Range: 0~2. |
| `buff_epoch` | `integer` | `1` | Buffer epoch. Range: 0~inf. |
| Name | Type | Default | Description |
| -------------------------- | --------- | ---------------- | ---------------------------------------------------------------------------------------------------------------------------------- |
| `base_frame` | `string` | `base_link` | frame id for base_frame |
| `gnss_base_frame` | `string` | `gnss_base_link` | frame id for gnss_base_frame |
| `map_frame` | `string` | `map` | frame id for map_frame |
| `use_gnss_ins_orientation` | `boolean` | `true` | use Gnss-Ins orientation |
| `gnss_pose_pub_method` | `integer` | `0` | 0: Instant Value 1: Average Value 2: Median Value. If `buffer_epoch` is set to 0, `gnss_pose_pub_method` loses affect. Range: 0~2. |
| `buff_epoch` | `integer` | `1` | Buffer epoch. Range: 0~inf. |

All above parameters can be changed in config file [gnss_poser.param.yaml](./config/gnss_poser.param.yaml "Click here to open config file") .
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,11 @@
#include <autoware/component_interface_specs/map.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/bool_stamped.hpp>
#include <autoware_sensing_msgs/msg/gnss_ins_orientation_stamped.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
#include <sensor_msgs/msg/nav_sat_fix.hpp>
#include <autoware_internal_debug_msgs/msg/bool_stamped.hpp>

#include <boost/circular_buffer.hpp>

Expand Down
2 changes: 1 addition & 1 deletion sensing/autoware_gnss_poser/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@

<depend>autoware_component_interface_specs</depend>
<depend>autoware_geography_utils</depend>
<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_sensing_msgs</depend>
<depend>geographic_msgs</depend>
<depend>geographiclib</depend>
Expand All @@ -32,7 +33,6 @@
<depend>tf2</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>autoware_internal_debug_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
3 changes: 2 additions & 1 deletion sensing/autoware_gnss_poser/src/gnss_poser_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,8 @@ GNSSPoser::GNSSPoser(const rclcpp::NodeOptions & node_options)
pose_pub_ = create_publisher<geometry_msgs::msg::PoseStamped>("gnss_pose", rclcpp::QoS{1});
pose_cov_pub_ = create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
"gnss_pose_cov", rclcpp::QoS{1});
fixed_pub_ = create_publisher<autoware_internal_debug_msgs::msg::BoolStamped>("gnss_fixed", rclcpp::QoS{1});
fixed_pub_ =
create_publisher<autoware_internal_debug_msgs::msg::BoolStamped>("gnss_fixed", rclcpp::QoS{1});

// Set msg_gnss_ins_orientation_stamped_ with temporary values (not to publish zero value
// covariances)
Expand Down

0 comments on commit 1202d17

Please sign in to comment.