Skip to content

Commit

Permalink
Merge branch 'main' into refactor/use_run_base_class_function
Browse files Browse the repository at this point in the history
Signed-off-by: kyoichi-sugahara <[email protected]>
  • Loading branch information
kyoichi-sugahara committed Nov 9, 2023
2 parents 9e63e94 + 0e471b3 commit c47ddae
Show file tree
Hide file tree
Showing 8 changed files with 50 additions and 12 deletions.
1 change: 1 addition & 0 deletions localization/gyro_odometer/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,4 +32,5 @@ endif()

ament_auto_package(INSTALL_TO_SHARE
launch
config
)
5 changes: 1 addition & 4 deletions localization/gyro_odometer/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -21,10 +21,7 @@

## Parameters

| Parameter | Type | Description |
| --------------------- | ------ | -------------------------------- |
| `output_frame` | String | output's frame id |
| `message_timeout_sec` | Double | delay tolerance time for message |
{{ json_to_markdown("localization/gyro_odometer/schema/gyro_odometer.schema.json") }}

## Assumptions / Known limits

Expand Down
4 changes: 4 additions & 0 deletions localization/gyro_odometer/config/gyro_odometer.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
/**:
ros__parameters:
output_frame: "base_link"
message_timeout_sec: 0.2
6 changes: 2 additions & 4 deletions localization/gyro_odometer/launch/gyro_odometer.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,7 @@
<arg name="output_twist_topic" default="gyro_twist" description="output twist topic name"/>
<arg name="output_twist_with_covariance_topic" default="gyro_twist_with_covariance" description="output twist with covariance topic name"/>

<arg name="output_frame" default="base_link" description="output frame id"/>
<arg name="message_timeout_sec" default="0.2" description="delay tolerance time for message"/>
<arg name="config_file" default="$(find-pkg-share gyro_odometer)/config/gyro_odometer.param.yaml"/>

<node pkg="gyro_odometer" exec="gyro_odometer" name="gyro_odometer" output="screen">
<remap from="vehicle/twist_with_covariance" to="$(var input_vehicle_twist_with_covariance_topic)"/>
Expand All @@ -23,7 +22,6 @@
<remap from="twist" to="$(var output_twist_topic)"/>
<remap from="twist_with_covariance" to="$(var output_twist_with_covariance_topic)"/>

<param name="output_frame" value="$(var output_frame)"/>
<param name="message_timeout_sec" value="$(var message_timeout_sec)"/>
<param from="$(var config_file)"/>
</node>
</launch>
38 changes: 38 additions & 0 deletions localization/gyro_odometer/schema/gyro_odometer.schema.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for gyro odometer",
"type": "object",
"definitions": {
"gyro_odometer": {
"type": "object",
"properties": {
"output_frame": {
"type": "string",
"description": "output's frame id",
"default": "base_link"
},
"message_timeout_sec": {
"type": "number",
"description": "delay tolerance time for message",
"default": 0.2
}
},
"required": ["output_frame", "message_timeout_sec"],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/gyro_odometer"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
4 changes: 2 additions & 2 deletions localization/gyro_odometer/src/gyro_odometer_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,8 +102,8 @@ geometry_msgs::msg::TwistWithCovarianceStamped concatGyroAndOdometer(

GyroOdometer::GyroOdometer(const rclcpp::NodeOptions & options)
: Node("gyro_odometer", options),
output_frame_(declare_parameter("output_frame", "base_link")),
message_timeout_sec_(declare_parameter("message_timeout_sec", 0.2)),
output_frame_(declare_parameter<std::string>("output_frame")),
message_timeout_sec_(declare_parameter<double>("message_timeout_sec")),
vehicle_twist_arrived_(false),
imu_arrived_(false)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -296,7 +296,7 @@ void GoalPlannerModule::processOnExit()

bool GoalPlannerModule::isExecutionRequested() const
{
if (current_state_ == ModuleStatus::RUNNING) {
if (getCurrentStatus() == ModuleStatus::RUNNING) {
return true;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -190,7 +190,7 @@ bool StartPlannerModule::isExecutionRequested() const

bool StartPlannerModule::isModuleRunning() const
{
return current_state_ == ModuleStatus::RUNNING;
return getCurrentStatus() == ModuleStatus::RUNNING;
}

bool StartPlannerModule::isCurrentPoseOnMiddleOfTheRoad() const
Expand Down

0 comments on commit c47ddae

Please sign in to comment.