Skip to content

f/687 lights device node#12

Open
ingibirka wants to merge 40 commits intomasterfrom
f/687-lights_device_node
Open

f/687 lights device node#12
ingibirka wants to merge 40 commits intomasterfrom
f/687-lights_device_node

Conversation

@ingibirka
Copy link
Copy Markdown

No description provided.

@leonard-pak
Copy link
Copy Markdown

МР не в ту ветку, сейчас там изменений на 200+ файлов))

Comment thread src/lights_node/lights/LICENSE Outdated
Copy link
Copy Markdown

Choose a reason for hiding this comment

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

лицензию в пакет можно не добавлять, она есть на весь репозиторий

Copy link
Copy Markdown

Choose a reason for hiding this comment

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

Давай не будем создавать отдельный пакет только под сообщения для твоей ноды. Лучше вынеси пакет из под light_node и переименуй в stingtray_,msgs

@@ -0,0 +1,27 @@
from setuptools import find_packages, setup

package_name = 'lights'
Copy link
Copy Markdown

Choose a reason for hiding this comment

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

давай переименуем пакет во что то более многозначное. например, light_manager или light_controller. можешь предлоджить свой вариант. и не забудь переименовать этот не только тут

Copy link
Copy Markdown

Choose a reason for hiding this comment

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

во многих файлах нет пустой строки в конце. в целом это должен делать форматер автоматом, если ты только не кодишь в блокноте)

Comment on lines +66 to +83
def main(args=None):
rclpy.init(args=args)
controller = LanternControl()

rclpy.spin(controller)

if controller.stop_effect_timer:
controller.stop_effect_timer.cancel()
if controller.publish_timer:
controller.publish_timer.cancel()
if controller.main_timer:
controller.main_timer.cancel()

controller.destroy_node()
rclpy.shutdown()

if __name__ == '__main__':
main() No newline at end of file
Copy link
Copy Markdown

Choose a reason for hiding this comment

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

Давай вынесем весь этот код в отдельный файл main.py

Comment thread src/lights_node/lights/lights/check.py Outdated
from rclpy.node import Node
from lights_interfaces.msg import Brightness

class LightDriver(Node):
Copy link
Copy Markdown

Choose a reason for hiding this comment

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

Не совсем понял, зачем надо делить на 2 ноды, всю эту логику можно уместить в рамках одной. Одна нода может подписываться и публиковать несколько топиков


from .code_light import BrightControl

class LanternControl(Node):
Copy link
Copy Markdown

Choose a reason for hiding this comment

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

Давай попробуем не наследоваться от Node, а инкапсулировать ее в класс. То есть создать self.node и работать с ним как с полем


class BrightControl:
def __init__(self):
self.mode = "SOLID"
Copy link
Copy Markdown

Choose a reason for hiding this comment

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

Давай использовать enum

from .code_light import BrightControl

class LanternControl(Node):
def __init__(self):
Copy link
Copy Markdown

Choose a reason for hiding this comment

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

Кажется нам нехватает подписки на какой нибудь топик, куда бы писали текущий режим работы света. Можно создать свое сообщение с подготовленными возможными значениями (типа enum)

shakuevda and others added 25 commits March 1, 2026 19:03
Create a new `stingray_interface_bridge` package that exposes
`SetTwist` and `SetStabilization` services and republishes requests to
control topics (`/control/data` and `/control/loop_flags`).

- Added node interface, executable wiring, and package build setup
- Added launch file with configurable service/topic names and QoS params
- Included loop-protection state handling and message/service dependencies

This enables clients to command Stingray through service APIs while
remaining compatible with the existing topic-based control pipeline.feat(interface-bridge): add ROS2 service-to-topic control bridge

Create a new `stingray_interface_bridge` package that exposes
`SetTwist` and `SetStabilization` services and republishes requests to
control topics (`/control/data` and `/control/loop_flags`).

- Added node interface, executable wiring, and package build setup
- Added launch file with configurable service/topic names and QoS params
- Included loop-protection state handling and message/service dependencies

This enables clients to command Stingray through service APIs while
remaining compatible with the existing topic-based control pipeline.
Add UV state aggregation to `stingray_interface_bridge` by subscribing to
IMU angular velocity, IMU linear acceleration, and depth topics, then
publishing a unified `stingray_core_interfaces/UVState` message.

Also update build and launch configuration to support this flow:
- add `vectornav_msgs` dependency
- add new subscribers/publisher and related handlers in `bridge_node`
- add launch arguments for `uv_state`, IMU, and depth topic names

This enables downstream nodes to consume a single vehicle state topic
instead of reading multiple raw sensor streams.feat(interface-bridge): publish UV state from IMU/depth

Add UV state aggregation to `stingray_interface_bridge` by subscribing to
IMU angular velocity, IMU linear acceleration, and depth topics, then
publishing a unified `stingray_core_interfaces/UVState` message.

Also update build and launch configuration to support this flow:
- add `vectornav_msgs` dependency
- add new subscribers/publisher and related handlers in `bridge_node`
- add launch arguments for `uv_state`, IMU, and depth topic names

This enables downstream nodes to consume a single vehicle state topic
instead of reading multiple raw sensor streams.
Stop generating `DeviceState`, `DeviceStateArray`, and `SetDevice` in
`stingray_core_interfaces` by removing them from `rosidl_generate_interfaces`.

This narrows the package to currently supported control/state interfaces and
avoids building unused device-specific messages/services.refactor(interfaces): remove device-related ROS IDL generation

Stop generating `DeviceState`, `DeviceStateArray`, and `SetDevice` in
`stingray_core_interfaces` by removing them from `rosidl_generate_interfaces`.

This narrows the package to currently supported control/state interfaces and
avoids building unused device-specific messages/services.
- Included `stingray_interfaces_bridge` in the `run_rov.sh` build script to ensure it is built alongside other packages.
- Updated `run_rov.launch.py` to include the launch description for `stingray_interfaces_bridge`, enabling its functionality within the ROV system.
- Adjusted `bridge_node.hpp` to correct the initialization of `last_pub_stamp_` for proper time handling.
- Modified `bridge_node.cpp` to use a more modern syntax for QoS configuration, enhancing code clarity.
Include `dvl_a50` in the ROV bringup flow so the DVL driver is built and launched with the rest of the core stack.

- add `dvl_a50` to the `colcon build` package list in `run_rov.sh`
- include `dvl_a50.launch.py` in `run_rov.launch.py`
- declare `dvl_a50` as an `exec_depend` in `stingray_core_launch/package.xml`

This ensures DVL components are available at runtime and start automatically during ROV launch.feat(launch): add dvl_a50 to ROV build and startup

Include `dvl_a50` in the ROV bringup flow so the DVL driver is built and launched with the rest of the core stack.

- add `dvl_a50` to the `colcon build` package list in `run_rov.sh`
- include `dvl_a50.launch.py` in `run_rov.launch.py`
- declare `dvl_a50` as an `exec_depend` in `stingray_core_launch/package.xml`

This ensures DVL components are available at runtime and start automatically during ROV launch.
Update ROV build and launch wiring to use `stingray_interface_bridge`
instead of the old pluralized package name in `run_rov.sh` and
`run_rov.launch.py`.

Also adjust the bridge package CMake install rule for the `launch`
directory path formatting so launch files are installed consistently.

This prevents package lookup/build issues caused by mismatched naming.fix(launch): correct stingray_interface_bridge references

Update ROV build and launch wiring to use `stingray_interface_bridge`
instead of the old pluralized package name in `run_rov.sh` and
`run_rov.launch.py`.

Also adjust the bridge package CMake install rule for the `launch`
directory path formatting so launch files are installed consistently.

This prevents package lookup/build issues caused by mismatched naming.
Update the default values for `input_service` and `input_stabilization_service` in both the launch file and bridge node parameters to `/stingray/services/set_twist` and `/stingray/services/set_stabilization`.

This aligns the bridge with the current Stingray service namespace and avoids manual remapping/configuration for default deployments.fix(stingray_interface_bridge): use namespaced service defaults

Update the default values for `input_service` and `input_stabilization_service` in both the launch file and bridge node parameters to `/stingray/services/set_twist` and `/stingray/services/set_stabilization`.

This aligns the bridge with the current Stingray service namespace and avoids manual remapping/configuration for default deployments.
- Replaced `stingray_core_interfaces` with `stingray_interfaces` in the interface bridge (CMake deps, includes, and service/message types) and added `stingray_interfaces` to `run_rov.sh` build targets.
- Updated `run_rov.launch.py` to pass explicit service names to `stingray_interface_bridge` (`/stingray/services/set_twist` and `/stingray/services/set_stabilization`) so bridge endpoints are wired consistently.
- Set a default `ROS_DOMAIN_ID` (`1`) in `docker/entrypoint.sh` to improve out-of-the-box ROS 2 communication in container runs.
- Commented out `thruster_link` and `vectornav` launch includes in `run_rov.launch.py` to avoid bringing up unused/unavailable components during this run path.fix(ros): migrate bridge to stingray_interfaces and set defaults

- Replaced `stingray_core_interfaces` with `stingray_interfaces` in the interface bridge (CMake deps, includes, and service/message types) and added `stingray_interfaces` to `run_rov.sh` build targets.
- Updated `run_rov.launch.py` to pass explicit service names to `stingray_interface_bridge` (`/stingray/services/set_twist` and `/stingray/services/set_stabilization`) so bridge endpoints are wired consistently.
- Set a default `ROS_DOMAIN_ID` (`1`) in `docker/entrypoint.sh` to improve out-of-the-box ROS 2 communication in container runs.
- Commented out `thruster_link` and `vectornav` launch includes in `run_rov.launch.py` to avoid bringing up unused/unavailable components during this run path.
Refactor control command handling to distinguish persistent closed-loop targets from transient open-loop commands.

- Add `control_input`, `control_setpoint`, and `open_loop_pending` per axis.
- Use `control_setpoint` for PID targets in enabled (closed-loop) axes.
- Apply open-loop commands for a single control cycle, then reset output to `0.0`.
- Store the actually applied command back into `control.impact`.
- On mode changes, initialize closed-loop setpoint from last input and clear pending open-loop pulses when disabling.

This prevents stale open-loop commands from being repeatedly applied and keeps closed-loop behavior stable across command and mode transitions.fix(control): separate setpoints from one-shot open-loop input

Refactor control command handling to distinguish persistent closed-loop targets from transient open-loop commands.

- Add `control_input`, `control_setpoint`, and `open_loop_pending` per axis.
- Use `control_setpoint` for PID targets in enabled (closed-loop) axes.
- Apply open-loop commands for a single control cycle, then reset output to `0.0`.
- Store the actually applied command back into `control.impact`.
- On mode changes, initialize closed-loop setpoint from last input and clear pending open-loop pulses when disabling.

This prevents stale open-loop commands from being repeatedly applied and keeps closed-loop behavior stable across command and mode transitions.
Introduce a new `std_srvs/Trigger` reset IMU service in the interface bridge and wire it to publish a `std_msgs/Bool` command on a configurable zero-yaw topic.

### What changed
- Added `std_srvs` as a package dependency in CMake.
- Extended `BridgeNode` with:
  - `handle_reset_imu(...)` service callback
  - `reset_imu_service_` service handle
  - `imu_zero_yaw_publisher_` publisher
  - new config fields for reset service and zero-yaw topic names
- Updated launch file to declare and pass:
  - `reset_imu_service` (default: `/stingray/services/reset_imu`)
  - `imu_zero_yaw_topic` (default: `/imu/zero_yaw`)

### Why
This enables external clients to request IMU yaw reset through a standard bridge service interface, improving operational control and integration flexibility without hardcoding topic/service names.feat(bridge): add IMU reset trigger and zero-yaw publishing

Introduce a new `std_srvs/Trigger` reset IMU service in the interface bridge and wire it to publish a `std_msgs/Bool` command on a configurable zero-yaw topic.

### What changed
- Added `std_srvs` as a package dependency in CMake.
- Extended `BridgeNode` with:
  - `handle_reset_imu(...)` service callback
  - `reset_imu_service_` service handle
  - `imu_zero_yaw_publisher_` publisher
  - new config fields for reset service and zero-yaw topic names
- Updated launch file to declare and pass:
  - `reset_imu_service` (default: `/stingray/services/reset_imu`)
  - `imu_zero_yaw_topic` (default: `/imu/zero_yaw`)

### Why
This enables external clients to request IMU yaw reset through a standard bridge service interface, improving operational control and integration flexibility without hardcoding topic/service names.
- Switch `stingray_core_control` telemetry publisher QoS reliability from `BEST_EFFORT` to `RELIABLE` to reduce dropped control/telemetry messages.
- Refactor `stingray_interface_bridge` twist handling to store the last requested twist and republish at 100 Hz via a timer.
- Add filtering helpers to publish only open-loop axis commands based on loop flags, and track republish state from incoming requests/flags.
- This keeps open-loop commands alive between service calls while preventing stale or conflicting commands on closed-loop axes.fix(control): improve twist delivery and telemetry QoS

- Switch `stingray_core_control` telemetry publisher QoS reliability from `BEST_EFFORT` to `RELIABLE` to reduce dropped control/telemetry messages.
- Refactor `stingray_interface_bridge` twist handling to store the last requested twist and republish at 100 Hz via a timer.
- Add filtering helpers to publish only open-loop axis commands based on loop flags, and track republish state from incoming requests/flags.
- This keeps open-loop commands alive between service calls while preventing stale or conflicting commands on closed-loop axes.
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

4 participants