@@ -117,22 +117,32 @@ JointTrajectoryController::state_interface_configuration() const
117
117
conf.names .push_back (joint_name + " /" + interface_type);
118
118
}
119
119
}
120
- conf.names .push_back (params_.speed_scaling_interface_name );
120
+ if (params_.exchange_scaling_factor_with_hardware )
121
+ {
122
+ conf.names .push_back (params_.speed_scaling_interface_name );
123
+ }
121
124
return conf;
122
125
}
123
126
124
127
controller_interface::return_type JointTrajectoryController::update (
125
128
const rclcpp::Time & time, const rclcpp::Duration & period)
126
129
{
127
- if (state_interfaces_. back (). get_name () == params_.speed_scaling_interface_name )
130
+ if (params_.exchange_scaling_factor_with_hardware )
128
131
{
129
- scaling_factor_ = state_interfaces_.back ().get_value ();
132
+ if (state_interfaces_.back ().get_name () == params_.speed_scaling_interface_name )
133
+ {
134
+ scaling_factor_ = state_interfaces_.back ().get_value ();
135
+ }
136
+ else
137
+ {
138
+ RCLCPP_ERROR (
139
+ get_node ()->get_logger (), " Speed scaling interface (%s) not found in hardware interface." ,
140
+ params_.speed_scaling_interface_name .c_str ());
141
+ }
130
142
}
131
143
else
132
144
{
133
- RCLCPP_ERROR (
134
- get_node ()->get_logger (), " Speed scaling interface (%s) not found in hardware interface." ,
135
- params_.speed_scaling_interface_name .c_str ());
145
+ scaling_factor_ = *(scaling_factor_rt_buff_.readFromRT ());
136
146
}
137
147
138
148
if (get_state ().id () == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
@@ -468,8 +478,7 @@ bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajecto
468
478
auto interface_has_values = [](const auto & joint_interface)
469
479
{
470
480
return std::find_if (
471
- joint_interface.begin (), joint_interface.end (),
472
- [](const auto & interface)
481
+ joint_interface.begin (), joint_interface.end (), [](const auto & interface)
473
482
{ return std::isnan (interface.get ().get_value ()); }) == joint_interface.end ();
474
483
};
475
484
@@ -539,8 +548,7 @@ bool JointTrajectoryController::read_commands_from_command_interfaces(
539
548
auto interface_has_values = [](const auto & joint_interface)
540
549
{
541
550
return std::find_if (
542
- joint_interface.begin (), joint_interface.end (),
543
- [](const auto & interface)
551
+ joint_interface.begin (), joint_interface.end (), [](const auto & interface)
544
552
{ return std::isnan (interface.get ().get_value ()); }) == joint_interface.end ();
545
553
};
546
554
@@ -900,10 +908,19 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
900
908
resize_joint_trajectory_point (state_error_, dof_);
901
909
resize_joint_trajectory_point (last_commanded_state_, dof_);
902
910
911
+ // create services
903
912
query_state_srv_ = get_node ()->create_service <control_msgs::srv::QueryTrajectoryState>(
904
913
std::string (get_node ()->get_name ()) + " /query_state" ,
905
914
std::bind (&JointTrajectoryController::query_state_service, this , _1, _2));
906
915
916
+ set_scaling_factor_srv_ = get_node ()->create_service <control_msgs::srv::SetScalingFactor>(
917
+ " ~/set_scaling_factor" , std::bind (
918
+ &JointTrajectoryController::set_scaling_factor, this ,
919
+ std::placeholders::_1, std::placeholders::_2));
920
+
921
+ // set scaling factor to low value default
922
+ scaling_factor_rt_buff_.writeFromNonRT (params_.scaling_factor_initial_default );
923
+
907
924
return CallbackReturn::SUCCESS;
908
925
}
909
926
@@ -1600,6 +1617,24 @@ void JointTrajectoryController::resize_joint_trajectory_point_command(
1600
1617
}
1601
1618
}
1602
1619
1620
+ bool JointTrajectoryController::set_scaling_factor (
1621
+ control_msgs::srv::SetScalingFactor::Request::SharedPtr req,
1622
+ control_msgs::srv::SetScalingFactor::Response::SharedPtr resp)
1623
+ {
1624
+ if (req->scaling_factor < 0 && req->scaling_factor > 1 )
1625
+ {
1626
+ RCLCPP_WARN (
1627
+ get_node ()->get_logger (), " Scaling factor has to be in range [0, 1]. Ignoring input!" );
1628
+ resp->success = false ;
1629
+ return true ;
1630
+ }
1631
+
1632
+ RCLCPP_INFO (get_node ()->get_logger (), " New scaling factor will be %f" , req->scaling_factor );
1633
+ scaling_factor_rt_buff_.writeFromNonRT (req->scaling_factor );
1634
+ resp->success = true ;
1635
+ return true ;
1636
+ }
1637
+
1603
1638
bool JointTrajectoryController::has_active_trajectory () const
1604
1639
{
1605
1640
return traj_external_point_ptr_ != nullptr && traj_external_point_ptr_->has_trajectory_msg ();
0 commit comments