Skip to content

Commit 254f2ec

Browse files
committed
Адреса теперь меняются из параметров
1 parent de8489c commit 254f2ec

File tree

7 files changed

+37
-9
lines changed

7 files changed

+37
-9
lines changed

src/Hydrolib-soft

Lines changed: 0 additions & 1 deletion
This file was deleted.

src/serial

Lines changed: 0 additions & 1 deletion
This file was deleted.

src/stingray_core_communication/stingray_core_communication/launch/pressure_link.launch.py

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,24 +17,31 @@ def generate_launch_description():
1717
'pressure.params.yaml'
1818
])
1919

20+
params_arg = DeclareLaunchArgument(
21+
'params_file',
22+
default_value=pressure_params_file,
23+
)
24+
2025
# Включение launch-файла serial_driver с передачей аргумента params_file
2126
serial_bridge_launch = IncludeLaunchDescription(
2227
PythonLaunchDescriptionSource(
2328
os.path.join(serial_driver_dir, 'launch', 'serial_driver_bridge_node.launch.py')
2429
),
2530
launch_arguments={
26-
'params_file': pressure_params_file,
31+
'params_file': LaunchConfiguration('params_file'),
2732

2833
}.items()
2934
)
3035

3136
return LaunchDescription([
37+
params_arg,
3238
serial_bridge_launch,
3339
Node(
3440
package='stingray_core_communication',
3541
executable='pressure_link_node',
3642
name='pressure_link_node',
43+
parameters=[LaunchConfiguration('params_file')],
3744

3845
output='screen'
3946
)
40-
])
47+
])

src/stingray_core_communication/stingray_core_communication/launch/thruster_link.launch.py

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,24 +17,31 @@ def generate_launch_description():
1717
'thruster.params.yaml'
1818
])
1919

20+
params_arg = DeclareLaunchArgument(
21+
'params_file',
22+
default_value=thruster_params_file,
23+
)
24+
2025
# Включение launch-файла serial_driver с передачей аргумента params_file
2126
serial_bridge_launch = IncludeLaunchDescription(
2227
PythonLaunchDescriptionSource(
2328
os.path.join(serial_driver_dir, 'launch', 'serial_driver_bridge_node.launch.py')
2429
),
2530
launch_arguments={
26-
'params_file': thruster_params_file,
31+
'params_file': LaunchConfiguration('params_file'),
2732

2833
}.items()
2934
)
3035

3136
return LaunchDescription([
37+
params_arg,
3238
serial_bridge_launch,
3339
Node(
3440
package='stingray_core_communication',
3541
executable='thrusters_driver_node',
3642
name='thrusters_driver_node',
43+
parameters=[LaunchConfiguration('params_file')],
3744

3845
output='screen'
3946
)
40-
])
47+
])

src/stingray_core_communication/stingray_core_communication/params/pressure.params.yaml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,7 @@
11
/**:
22
ros__parameters:
3+
self_addr: 2
4+
dev_addr: 1
35
device_name: /dev/serial1
46
baud_rate: 115200
57
flow_control: none

src/stingray_core_communication/stingray_core_communication/params/thruster.params.yaml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,7 @@
11
/**:
22
ros__parameters:
3+
self_addr: 2
4+
dev_addr: 1
35
device_name: /dev/serial0
46
baud_rate: 115200
57
flow_control: none

src/stingray_core_communication/stingray_core_communication/src/link_node_base.hpp

Lines changed: 15 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -57,8 +57,10 @@ class LinkNodeBase : public rclcpp::Node
5757
LinkNodeBase(std::string node_name, int self_addr, int dev_addr, MemoryReadCallback read_cb, MemoryWriteCallback write_cb)
5858
: Node(std::move(node_name)),
5959
mode_(read_cb && write_cb ? Mode::kSlave : Mode::kMaster),
60-
stream_manager_(self_addr, *this, logger),
61-
stream_(stream_manager_, dev_addr),
60+
self_addr_(declareAddressParameter("self_addr", self_addr)),
61+
dev_addr_(declareAddressParameter("dev_addr", dev_addr)),
62+
stream_manager_(self_addr_, *this, logger),
63+
stream_(stream_manager_, dev_addr_),
6264
master_(stream_, logger),
6365
slave_memory_(std::move(read_cb), std::move(write_cb)),
6466
slave_(stream_, slave_memory_, logger)
@@ -68,7 +70,10 @@ class LinkNodeBase : public rclcpp::Node
6870
"serial_read", 20, std::bind(&LinkNodeBase::readCallback, this, std::placeholders::_1));
6971
hydrolib_RingQueue_Init(&tx_queue_, work_buf_tx_queue_.data(), kQueueLen);
7072

71-
RCLCPP_INFO(this->get_logger(), "Link node initialized in %s mode", mode_ == Mode::kMaster ? "master" : "slave");
73+
RCLCPP_INFO(
74+
this->get_logger(),
75+
"Link node initialized in %s mode (self_addr=%d, dev_addr=%d)",
76+
mode_ == Mode::kMaster ? "master" : "slave", self_addr_, dev_addr_);
7277
}
7378

7479
public:
@@ -107,6 +112,11 @@ class LinkNodeBase : public rclcpp::Node
107112
}
108113

109114
private:
115+
int declareAddressParameter(const char *name, int default_value)
116+
{
117+
return this->declare_parameter<int>(name, default_value);
118+
}
119+
110120
enum class Mode
111121
{
112122
kMaster,
@@ -166,6 +176,8 @@ class LinkNodeBase : public rclcpp::Node
166176
}
167177

168178
Mode mode_;
179+
int self_addr_;
180+
int dev_addr_;
169181

170182
rclcpp::Subscription<std_msgs::msg::UInt8MultiArray>::SharedPtr serial_sub_;
171183
rclcpp::Publisher<std_msgs::msg::UInt8MultiArray>::SharedPtr serial_pub_;

0 commit comments

Comments
 (0)