Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Launch引数指定 #55

Merged
merged 17 commits into from
Aug 6, 2024
Merged
8 changes: 6 additions & 2 deletions app/imshow/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,12 @@ USBカメラの映像を映す

## Executables

- `imshow`: `imshow`Nodeをspin

- `imshow`: `Imshow`Nodeをspin

## Launches

- `imshow_launch.py`: `Imshow`Nodeをspinする。以下のlaunch引数をとる
- `index`: 受け取る画像のインデックス。
与えられた場合はtopic`/app/camera_image`が`/packet/camera_image_{index}`にremapされ、
Nodeの名前が`imshow_{index}`に変わる。
与えられなかった場合はtopic`/app/camera_image`が`/packet/camera_image`にremapされる(Nodeの名前はそのまま)。
43 changes: 33 additions & 10 deletions app/imshow/launch/imshow_launch.py
Original file line number Diff line number Diff line change
@@ -1,15 +1,38 @@
from typing import Any

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.conditions import IfCondition, UnlessCondition
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import Node


def generate_launch_description():
return LaunchDescription(
[
Node(
package="imshow",
executable="imshow",
namespace="app",
remappings=[("/app/camera_image", "/packet/camera_image")],
),
],
def imshow_node(**kwargs: Any) -> Node:
kwargs["package"] = "imshow"
kwargs["executable"] = "imshow"
kwargs["namespace"] = "app"
return Node(**kwargs)


def generate_launch_description() -> LaunchDescription:
index_arg = DeclareLaunchArgument("index", default_value="-1")
log_level_arg = DeclareLaunchArgument(
"log_level",
default_value="info",
choices=["debug", "info", "warn", "error", "fatal"],
)
index = LaunchConfiguration("index")
log_level = LaunchConfiguration("log_level")
index_specified = PythonExpression([index, ">= 0"])
indexed_imshow = imshow_node(
name=["imshow_", index],
remappings=[("/app/camera_image", ["/packet/camera_image_", index])],
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

["/packet/camera_image_", index]

は文字列の結合のようなことをしているのでしょうか?

f"/packet/camera_image_{index}"

などしないのは、indexLaunchConfiguration()の返り値であることと関係がありますか?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

文字列の結合のようなことをしているのでしょうか?

はい。

indexLaunchConfiguration()の返り値であることと関係がありますか?

はい。これはlaunchファイルのsubstitutionという機能で、launchの実行時に文字列の結合が行われます。例えばros2 launch --show-args imshow imshow_launch.pyではlaunchの読み込みのみが行われて該当部分の文字列の結合は発生しません。

ref: ROS2を深く理解する:launchファイル編2 substitution

ros_arguments=["--log-level", log_level],
condition=IfCondition(index_specified),
)
unindexed_imshow = imshow_node(
remappings=[("/app/camera_image", "/packet/camera_image")],
ros_arguments=["--log-level", log_level],
condition=UnlessCondition(index_specified),
)
return LaunchDescription([index_arg, log_level_arg, indexed_imshow, unindexed_imshow])
6 changes: 4 additions & 2 deletions app/power_map/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,9 @@

## Launches

- `launch.py`:
- `power_map_launch.py`:
`power_map`Nodeに`config/default_param.yml`でparameterを与えつつ、それを実行する。
その際`app`namespaceが適用され、出力の`/app/power`topicは`/device/order/power`topicにremapされる
(出力先は`device/nucleo_communicate_py`を参照)。
(出力先は`device/nucleo_communicate_py`を参照)。以下のlaunch引数を持つ
- `param_file`: パラメータの値を指定するYAMLファイルへのパス。
デフォルトでは`./config/default_param.yml`が使用される。
24 changes: 0 additions & 24 deletions app/power_map/launch/launch.py

This file was deleted.

27 changes: 27 additions & 0 deletions app/power_map/launch/power_map_launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare


def generate_launch_description():
param_file = PathJoinSubstitution(
[FindPackageShare("power_map"), "config", "default_param.yml"]
)
param_file_arg = DeclareLaunchArgument("param_file", default_value=param_file)
log_level_arg = DeclareLaunchArgument(
"log_level",
default_value="info",
choices=["debug", "info", "warn", "error", "fatal"],
)
log_level = LaunchConfiguration("log_level")
power_map = Node(
package="power_map",
executable="power-map",
namespace="app",
parameters=[LaunchConfiguration("param_file")],
remappings=[("/app/power", "/device/order/power")],
ros_arguments=["--log-level", log_level],
)
return LaunchDescription([param_file_arg, log_level_arg, power_map])
29 changes: 19 additions & 10 deletions app/power_map/src/power_map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,53 +22,62 @@ void power_map::PowerMap::publish_order(packet_interfaces::msg::Power& msg) {
auto power_map::PowerMap::create_bldc_center_cb(size_t i
) -> rclcpp::ParameterCallbackHandle::ParameterCallbackType {
return [this, i](const rclcpp::Parameter& p) {
const int64_t v = p.as_int();
RCLCPP_INFO_STREAM(
this->get_logger(),
"received parameter update of " << "bldc_center" << (i + 1)
"received parameter update of " << "bldc_center" << (i + 1) << " = " << v
);
this->configs[i].bldc_center(p.as_int());
this->configs[i].bldc_center(v);
};
}

auto power_map::PowerMap::create_bldc_positive_radius_cb(size_t i
) -> rclcpp::ParameterCallbackHandle::ParameterCallbackType {
return [this, i](const rclcpp::Parameter& p) {
const int64_t v = p.as_int();
RCLCPP_INFO_STREAM(
this->get_logger(),
"received parameter update of " << "bldc_positive_radius" << (i + 1)
"received parameter update of " << "bldc_positive_radius" << (i + 1) << " = "
<< v
);
this->configs[i].bldc_positive_radius(p.as_int());
this->configs[i].bldc_positive_radius(v);
};
}

auto power_map::PowerMap::create_bldc_negative_radius_cb(size_t i
) -> rclcpp::ParameterCallbackHandle::ParameterCallbackType {
return [this, i](const rclcpp::Parameter& p) {
const int64_t v = p.as_int();
RCLCPP_INFO_STREAM(
this->get_logger(),
"received parameter update of " << "bldc_negative_radius" << (i + 1)
"received parameter update of " << "bldc_negative_radius" << (i + 1) << " = "
<< v
);
this->configs[i].bldc_negative_radius(p.as_int());
this->configs[i].bldc_negative_radius(v);
};
}

auto power_map::PowerMap::create_servo_min_cb(size_t i
) -> rclcpp::ParameterCallbackHandle::ParameterCallbackType {
return [this, i](const rclcpp::Parameter& p) {
const int64_t v = p.as_int();
RCLCPP_INFO_STREAM(
this->get_logger(), "received parameter update of " << "servo_min" << (i + 1)
this->get_logger(),
"received parameter update of " << "servo_min" << (i + 1) << " = " << v
);
this->configs[i].servo_min(p.as_int());
this->configs[i].servo_min(v);
};
}

auto power_map::PowerMap::create_servo_max_cb(size_t i
) -> rclcpp::ParameterCallbackHandle::ParameterCallbackType {
return [this, i](const rclcpp::Parameter& p) {
const int64_t v = p.as_int();
RCLCPP_INFO_STREAM(
this->get_logger(), "received parameter update of " << "servo_max" << (i + 1)
this->get_logger(),
"received parameter update of " << "servo_max" << (i + 1) << " = " << v
);
this->configs[i].servo_max(p.as_int());
this->configs[i].servo_max(v);
};
}

Expand Down
24 changes: 15 additions & 9 deletions app/simple_joy_app/launch/app_launch.py
Original file line number Diff line number Diff line change
@@ -1,15 +1,21 @@
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node


def generate_launch_description():
return LaunchDescription(
[
Node(
package="simple_joy_app",
executable="app",
namespace="app",
remappings=[("/app/joystick", "/packet/joystick")],
),
],
log_level_arg = DeclareLaunchArgument(
"log_level",
default_value="info",
choices=["debug", "info", "warn", "error", "fatal"],
)
log_level = LaunchConfiguration("log_level")
app = Node(
package="simple_joy_app",
executable="app",
namespace="app",
remappings=[("/app/joystick", "/packet/joystick")],
ros_arguments=["--log-level", log_level],
)
return LaunchDescription([log_level_arg, app])
8 changes: 8 additions & 0 deletions device/camera_reader/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -11,3 +11,11 @@ USBカメラの映像を取得
- `camera`: `Camera`Nodeをspin

## Launches

- `camera_reader_launch.py`: `Camera`Nodeをspinする。以下のlaunch引数が与えられる
- `index`: カメラの番号。
与えられた場合は`/dev/video{index}`に該当するカメラを参照し、
topic`/app/camera_image`が`/packet/camera_image_{index}`にremapされ、
Nodeの名前が`camera_{index}`に変わる。
与えられなかった場合は`/dev/video0`に該当するカメラを参照し、
topic`/app/camera_image`が`/packet/camera_image`にremapされる。
50 changes: 34 additions & 16 deletions device/camera_reader/launch/camera_reader_launch.py
Original file line number Diff line number Diff line change
@@ -1,24 +1,42 @@
import os
from typing import Any

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.conditions import IfCondition, UnlessCondition
from launch.substitutions import (
LaunchConfiguration,
PathJoinSubstitution,
PythonExpression,
)
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare


def generate_launch_description():
config = os.path.join(
get_package_share_directory("camera_reader"),
"config",
"default_param.yml",
def camera_node(**kwargs: Any) -> Node:
kwargs["package"] = "camera_reader"
kwargs["executable"] = "camera"
kwargs["namespace"] = "device"
return Node(**kwargs)


def generate_launch_description() -> LaunchDescription:
index_arg = DeclareLaunchArgument("index", default_value="-1")
index = LaunchConfiguration("index")
index_specified = PythonExpression([index, ">= 0"])
default_config_path = PathJoinSubstitution(
[FindPackageShare("camera_reader"), "config", "default_param.yml"]
)
use_index = camera_node(
name=["camera_", index],
parameters=[{"camera_id": index}],
remappings=[("/device/camera_image", ["/packet/camera_image_", index])],
condition=IfCondition(index_specified),
)
unuse_index = camera_node(
parameters=[default_config_path],
remappings=[("/device/camera_image", "/packet/camera_image")],
condition=UnlessCondition(index_specified),
)
return LaunchDescription(
[
Node(
package="camera_reader",
executable="camera",
namespace="device",
parameters=[config],
remappings=[("/device/camera_image", "/packet/camera_image")],
),
],
[index_arg, use_index, unuse_index],
)
2 changes: 1 addition & 1 deletion device/nucleo_communicate/launch/channel_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ def generate_launch_description():
("/device/voltage", "/packet/sensors/voltage"),
# FIXME: /packet namespaceにremap
("/device/power", "/device/order/power"),
("/device/quit", "/device/order/quit")
("/device/quit", "/device/order/quit"),
],
)
return LaunchDescription([channel])
2 changes: 1 addition & 1 deletion device/nucleo_communicate_py/launch/channel_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,6 @@ def generate_launch_description() -> LaunchDescription:
("/device/flex_2", "/packet/sensors/flex_2"),
("/device/current", "/packet/sensor/current"),
("/device/voltage", "/packet/sensor/voltage"),
]
],
)
return LaunchDescription([main])
33 changes: 33 additions & 0 deletions device/pi_led/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
# pi_led

ラズパイのGPIOでLED(フルカラー)を扱う

## Nodes

- `Led`: LEDを扱う。以下のparameterを(起動時のみ)受け取る
- `led_pin_r`: Redのピン
- `led_pin_g`: Greenのピン
- `led_pin_b`: Blueのピン

parameterの設定例は./config以下を参照

## Executables

- `pi_led`: `Led`Nodeをspinする

## Launches

- `led_launch.py`: `Led`Nodeを`device`namespace下でspinする。以下のlaunch引数が与えられる
- `variant`: 使用するGPIO Pinセットの略称。`default`, `right`, `left`, `custom`のいずれか
- `default`: ./config/default_param.ymlのparameter設定でspinする。
topic`/device/led_color`が`/packet/order/led_color`にremapされる
- `right`: ./config/default_param.ymlのparameter設定でspinする。
Node名が`led_right`に書きかわり、
topic`/device/led_color`が`/packet/order/led_color_right`にremapされる
- `left`: ./config/left_param.ymlのparameter設定でspinする。
Node名が`led_left`に書きかわり、
topic`/device/led_color`が`/packet/order/led_color_left`にremapされる
- `custom`: launch引数`param_file`で指定されたparameterでspinする。
Node名が`led_custom`に書きかわり、
topic`/device/led_color`が`/packet/order/led_color_custom`にremapされる
- `param_file`: カスタムのparameter設定ファイル。`variant:=custom`の時のみ有効
Loading