Skip to content

Commit 2dccb5a

Browse files
Fix temporary copies of other semantic components (#1905)
1 parent 3d88b7c commit 2dccb5a

File tree

4 files changed

+13
-11
lines changed

4 files changed

+13
-11
lines changed

admittance_controller/src/admittance_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -338,7 +338,7 @@ controller_interface::CallbackReturn AdmittanceController::on_configure(
338338

339339
// Initialize FTS semantic semantic_component
340340
force_torque_sensor_ = std::make_unique<semantic_components::ForceTorqueSensor>(
341-
semantic_components::ForceTorqueSensor(admittance_->parameters_.ft_sensor.name));
341+
admittance_->parameters_.ft_sensor.name);
342342

343343
// configure admittance rule
344344
if (

gps_sensor_broadcaster/src/gps_sensor_broadcaster.cpp

Lines changed: 10 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -56,12 +56,16 @@ callback_return_type GPSSensorBroadcaster::on_configure(const rclcpp_lifecycle::
5656
param_listener_->refresh_dynamic_parameters();
5757
params_ = param_listener_->get_params();
5858

59-
gps_sensor_ =
60-
params_.read_covariance_from_interface
61-
? GPSSensorVariant{semantic_components::GPSSensor<GPSSensorOption::WithCovariance>(
62-
params_.sensor_name)}
63-
: GPSSensorVariant{
64-
semantic_components::GPSSensor<GPSSensorOption::WithoutCovariance>(params_.sensor_name)};
59+
if (params_.read_covariance_from_interface)
60+
{
61+
gps_sensor_.emplace<semantic_components::GPSSensor<GPSSensorOption::WithCovariance>>(
62+
params_.sensor_name);
63+
}
64+
else
65+
{
66+
gps_sensor_.emplace<semantic_components::GPSSensor<GPSSensorOption::WithoutCovariance>>(
67+
params_.sensor_name);
68+
}
6569
std::visit(
6670
Visitor{
6771
[this](auto & sensor) { state_names_ = sensor.get_state_interface_names(); },

imu_sensor_broadcaster/src/imu_sensor_broadcaster.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -59,8 +59,7 @@ controller_interface::CallbackReturn IMUSensorBroadcaster::on_configure(
5959
return CallbackReturn::ERROR;
6060
}
6161

62-
imu_sensor_ = std::make_unique<semantic_components::IMUSensor>(
63-
semantic_components::IMUSensor(params_.sensor_name));
62+
imu_sensor_ = std::make_unique<semantic_components::IMUSensor>(params_.sensor_name);
6463
try
6564
{
6665
// register ft sensor data publisher

range_sensor_broadcaster/src/range_sensor_broadcaster.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -56,8 +56,7 @@ controller_interface::CallbackReturn RangeSensorBroadcaster::on_configure(
5656
return CallbackReturn::ERROR;
5757
}
5858

59-
range_sensor_ = std::make_unique<semantic_components::RangeSensor>(
60-
semantic_components::RangeSensor(params_.sensor_name));
59+
range_sensor_ = std::make_unique<semantic_components::RangeSensor>(params_.sensor_name);
6160
try
6261
{
6362
// register ft sensor data publisher

0 commit comments

Comments
 (0)