-
Notifications
You must be signed in to change notification settings - Fork 389
Add AckermannDriveStamped control to steering library #1563
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
base: master
Are you sure you want to change the base?
Changes from 11 commits
768ef15
e22df84
36bc9d5
94eebd0
c0f103e
0564ada
eaebf09
3e84edd
4f14831
e20e63c
031ddc6
7564e34
0c3ded5
a15dc7f
66effcf
d204e7e
948b67c
c612f3c
915e3bd
b038514
b79d682
f9f2459
3782090
aae242d
abbe4fd
fc881c2
5a6e60e
ed3ef21
8b65ff9
976935a
bb27729
b42d13a
c367db2
3436bb0
8d9cc8e
8a60aa3
f159c60
1fd197c
9c8bb76
f150a9b
d01dd0f
1b7cf57
990d2fe
ef29f5f
9d8bd04
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change | ||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
@@ -28,10 +28,12 @@ namespace | |||||||||
|
||||||||||
using ControllerTwistReferenceMsg = | ||||||||||
steering_controllers_library::SteeringControllersLibrary::ControllerTwistReferenceMsg; | ||||||||||
using ControllerAckermannReferenceMsg = | ||||||||||
steering_controllers_library::SteeringControllersLibrary::ControllerAckermannReferenceMsg; | ||||||||||
|
||||||||||
// called from RT control loop | ||||||||||
void reset_controller_reference_msg( | ||||||||||
const std::shared_ptr<ControllerTwistReferenceMsg> & msg, | ||||||||||
const std::shared_ptr<ControllerTwistReferenceMsg> & msg, | ||||||||||
const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node) | ||||||||||
{ | ||||||||||
msg->header.stamp = node->now(); | ||||||||||
|
@@ -43,6 +45,18 @@ void reset_controller_reference_msg( | |||||||||
msg->twist.angular.z = std::numeric_limits<double>::quiet_NaN(); | ||||||||||
} | ||||||||||
|
||||||||||
void reset_controller_reference_msg( | ||||||||||
const std::shared_ptr<ControllerAckermannReferenceMsg> & msg, | ||||||||||
const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node) | ||||||||||
{ | ||||||||||
msg->header.stamp = node->now(); | ||||||||||
msg->drive.speed = std::numeric_limits<double>::quiet_NaN(); | ||||||||||
msg->drive.acceleration = std::numeric_limits<double>::quiet_NaN(); | ||||||||||
msg->drive.jerk = std::numeric_limits<double>::quiet_NaN(); | ||||||||||
msg->drive.steering_angle = std::numeric_limits<double>::quiet_NaN(); | ||||||||||
msg->drive.steering_angle_velocity = std::numeric_limits<double>::quiet_NaN(); | ||||||||||
} | ||||||||||
|
||||||||||
} // namespace | ||||||||||
|
||||||||||
namespace steering_controllers_library | ||||||||||
|
@@ -111,14 +125,22 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure( | |||||||||
|
||||||||||
// Reference Subscriber | ||||||||||
ref_timeout_ = rclcpp::Duration::from_seconds(params_.reference_timeout); | ||||||||||
ref_subscriber_twist_ = get_node()->create_subscription<ControllerTwistReferenceMsg>( | ||||||||||
"~/reference", subscribers_qos, | ||||||||||
std::bind(&SteeringControllersLibrary::reference_callback, this, std::placeholders::_1)); | ||||||||||
|
||||||||||
std::shared_ptr<ControllerTwistReferenceMsg> msg = | ||||||||||
std::make_shared<ControllerTwistReferenceMsg>(); | ||||||||||
reset_controller_reference_msg(msg, get_node()); | ||||||||||
input_ref_.writeFromNonRT(msg); | ||||||||||
if (params_.twist_input) { | ||||||||||
ref_subscriber_twist_ = get_node()->create_subscription<ControllerTwistReferenceMsg>( | ||||||||||
"~/reference", subscribers_qos, | ||||||||||
std::bind(&SteeringControllersLibrary::reference_callback_twist, this, std::placeholders::_1)); | ||||||||||
std::shared_ptr<ControllerTwistReferenceMsg> msg = std::make_shared<ControllerTwistReferenceMsg>(); | ||||||||||
reset_controller_reference_msg(msg, get_node()); | ||||||||||
input_ref_twist_.writeFromNonRT(msg); | ||||||||||
} else { | ||||||||||
ref_subscriber_ackermann_ = get_node()->create_subscription<ControllerAckermannReferenceMsg>( | ||||||||||
"~/reference", subscribers_qos, | ||||||||||
std::bind(&SteeringControllersLibrary::reference_callback_ackermann, this, std::placeholders::_1)); | ||||||||||
std::shared_ptr<ControllerAckermannReferenceMsg> msg = std::make_shared<ControllerAckermannReferenceMsg>(); | ||||||||||
reset_controller_reference_msg(msg, get_node()); | ||||||||||
input_ref_ackermann_.writeFromNonRT(msg); | ||||||||||
} | ||||||||||
|
||||||||||
try | ||||||||||
{ | ||||||||||
|
@@ -200,7 +222,7 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure( | |||||||||
return controller_interface::CallbackReturn::SUCCESS; | ||||||||||
} | ||||||||||
|
||||||||||
void SteeringControllersLibrary::reference_callback( | ||||||||||
void SteeringControllersLibrary::reference_callback_twist( | ||||||||||
const std::shared_ptr<ControllerTwistReferenceMsg> msg) | ||||||||||
{ | ||||||||||
// if no timestamp provided use current time for command timestamp | ||||||||||
|
@@ -215,7 +237,35 @@ void SteeringControllersLibrary::reference_callback( | |||||||||
|
||||||||||
if (ref_timeout_ == rclcpp::Duration::from_seconds(0) || age_of_last_command <= ref_timeout_) | ||||||||||
{ | ||||||||||
input_ref_.writeFromNonRT(msg); | ||||||||||
input_ref_twist_.writeFromNonRT(msg); | ||||||||||
} | ||||||||||
else | ||||||||||
{ | ||||||||||
RCLCPP_ERROR( | ||||||||||
get_node()->get_logger(), | ||||||||||
"Received message has timestamp %.10f older for %.10f which is more then allowed timeout " | ||||||||||
"(%.4f).", | ||||||||||
rclcpp::Time(msg->header.stamp).seconds(), age_of_last_command.seconds(), | ||||||||||
ref_timeout_.seconds()); | ||||||||||
} | ||||||||||
} | ||||||||||
|
||||||||||
void SteeringControllersLibrary::reference_callback_ackermann( | ||||||||||
const std::shared_ptr<ControllerAckermannReferenceMsg> msg) | ||||||||||
{ | ||||||||||
// if no timestamp provided use current time for command timestamp | ||||||||||
if (msg->header.stamp.sec == 0 && msg->header.stamp.nanosec == 0u) | ||||||||||
{ | ||||||||||
RCLCPP_WARN( | ||||||||||
get_node()->get_logger(), | ||||||||||
"Timestamp in header is missing, using current time as command timestamp."); | ||||||||||
msg->header.stamp = get_node()->now(); | ||||||||||
} | ||||||||||
const auto age_of_last_command = get_node()->now() - msg->header.stamp; | ||||||||||
|
||||||||||
if (ref_timeout_ == rclcpp::Duration::from_seconds(0) || age_of_last_command <= ref_timeout_) | ||||||||||
{ | ||||||||||
input_ref_ackermann_.writeFromNonRT(msg); | ||||||||||
} | ||||||||||
else | ||||||||||
{ | ||||||||||
|
@@ -337,7 +387,12 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_activate( | |||||||||
const rclcpp_lifecycle::State & /*previous_state*/) | ||||||||||
{ | ||||||||||
// Set default value in command | ||||||||||
reset_controller_reference_msg(*(input_ref_.readFromRT()), get_node()); | ||||||||||
if(ref_subscriber_twist_ != nullptr){ | ||||||||||
reset_controller_reference_msg(*(input_ref_twist_.readFromRT()), get_node()); | ||||||||||
} | ||||||||||
if(ref_subscriber_ackermann_ != nullptr){ | ||||||||||
reset_controller_reference_msg(*(input_ref_ackermann_.readFromRT()), get_node()); | ||||||||||
} | ||||||||||
|
||||||||||
return controller_interface::CallbackReturn::SUCCESS; | ||||||||||
} | ||||||||||
|
@@ -355,12 +410,23 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_deactivate( | |||||||||
controller_interface::return_type SteeringControllersLibrary::update_reference_from_subscribers( | ||||||||||
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) | ||||||||||
{ | ||||||||||
auto current_ref = *(input_ref_.readFromRT()); | ||||||||||
|
||||||||||
if (!std::isnan(current_ref->twist.linear.x) && !std::isnan(current_ref->twist.angular.z)) | ||||||||||
if(params_.twist_input) | ||||||||||
{ | ||||||||||
auto current_ref = *(input_ref_twist_.readFromRT()); | ||||||||||
if (!std::isnan(current_ref->twist.linear.x) && !std::isnan(current_ref->twist.angular.z)) | ||||||||||
{ | ||||||||||
reference_interfaces_[0] = current_ref->twist.linear.x; | ||||||||||
reference_interfaces_[1] = current_ref->twist.angular.z; | ||||||||||
} | ||||||||||
} | ||||||||||
else | ||||||||||
{ | ||||||||||
reference_interfaces_[0] = current_ref->twist.linear.x; | ||||||||||
reference_interfaces_[1] = current_ref->twist.angular.z; | ||||||||||
auto current_ref = *(input_ref_ackermann_.readFromRT()); | ||||||||||
if (!std::isnan(current_ref->drive.speed) && !std::isnan(current_ref->drive.steering_angle)) | ||||||||||
{ | ||||||||||
reference_interfaces_[0] = current_ref->drive.speed; | ||||||||||
reference_interfaces_[1] = current_ref->drive.steering_angle; | ||||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
I have a question: If we only use speed and steering_angle, is it a good idea to use the full blown ackermann_msg definition? Furthermore, I am reluctant using a message type called ackermann_msg, even if the robot has no ackermann kinematics. Is there a reason for that, for example an upstream package which publishes in this format? Otherwise, I'd suggest to add a new message similar to this to control_msgs repository. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I mainly used this message since it was already present prior to the removal of the message publisher of this type in the initial draft of this PR. I initially also thought that it may be good to have some cross-compatibility, but I am not aware of big projects that use this message atm. So I don't have any hard feelings on using a custom message for this. How would you call it instead? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
A good question 😁 Maybe simply There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Good idea, I created a PR: ros-controls/control_msgs#217 |
||||||||||
} | ||||||||||
} | ||||||||||
|
||||||||||
return controller_interface::return_type::OK; | ||||||||||
|
@@ -378,7 +444,10 @@ controller_interface::return_type SteeringControllersLibrary::update_and_write_c | |||||||||
|
||||||||||
if (!std::isnan(reference_interfaces_[0]) && !std::isnan(reference_interfaces_[1])) | ||||||||||
{ | ||||||||||
const auto age_of_last_command = time - (*(input_ref_.readFromRT()))->header.stamp; | ||||||||||
const auto age_of_last_command = params_.twist_input ? | ||||||||||
time - (*(input_ref_twist_.readFromRT()))->header.stamp : | ||||||||||
time - (*(input_ref_ackermann_.readFromRT()))->header.stamp; | ||||||||||
|
||||||||||
const auto timeout = | ||||||||||
age_of_last_command > ref_timeout_ && ref_timeout_ != rclcpp::Duration::from_seconds(0); | ||||||||||
|
||||||||||
|
@@ -388,7 +457,9 @@ controller_interface::return_type SteeringControllersLibrary::update_and_write_c | |||||||||
|
||||||||||
auto [traction_commands, steering_commands] = odometry_.get_commands( | ||||||||||
reference_interfaces_[0], reference_interfaces_[1], params_.open_loop, | ||||||||||
params_.reduce_wheel_speed_until_steering_reached); | ||||||||||
params_.reduce_wheel_speed_until_steering_reached, | ||||||||||
params_.twist_input | ||||||||||
); | ||||||||||
|
||||||||||
if (params_.front_steering) | ||||||||||
{ | ||||||||||
|
Uh oh!
There was an error while loading. Please reload this page.