Skip to content

Feature/waypoint controller base#20

Open
Excelsius314 wants to merge 10 commits intojazzyfrom
feature/waypoint_controller_base
Open

Feature/waypoint controller base#20
Excelsius314 wants to merge 10 commits intojazzyfrom
feature/waypoint_controller_base

Conversation

@Excelsius314
Copy link
Contributor

No description provided.

@Excelsius314
Copy link
Contributor Author

@Excelsius314 Excelsius314 requested a review from Joschi3 February 4, 2026 14:01
@Excelsius314 Excelsius314 self-assigned this Feb 4, 2026
@Joschi3
Copy link
Member

Joschi3 commented Feb 4, 2026

And: https://github.com/tu-darmstadt-ros-pkg/realtime_tools/tree/feature/lock_free_write
Do you want to create a merge request for this branch?

@@ -0,0 +1,9 @@
geometry_msgs/Point[] waypoint_trajectory
Copy link
Member

Choose a reason for hiding this comment

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

Do we want to store orientations too? I guess we need at least a yaw angle for the last position. We could change it too geometry_msgs/Pose[]

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Added a separate float array for headings for now, to keep it more readable. But I am open to replace with geometry_msgs/Pose

@@ -0,0 +1,22 @@
# hector_ros_controllers_msgs
Copy link
Member

Choose a reason for hiding this comment

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

Please provide a short overview of the msgs package.

Copy link
Member

Choose a reason for hiding this comment

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

Also update the top-level readme to include the waypoint controller

Waypoint()
{
x = 0.0;
y = 0.0;
Copy link
Member

Choose a reason for hiding this comment

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

What about the (final) orientation?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Added headings to the waipoints

geometry_msgs::msg::TransformStamped t;

try {
t = tf_buffer_->lookupTransform( "map", base_link_frame_, tf2::TimePointZero );
Copy link
Member

Choose a reason for hiding this comment

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

Prefer not to hardcode any frames.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Done

std::pow( goal.y - current_pose.y, 2 ) ) <= goal_completion_tolerance_;
}

// Simple placeholder implementation for testing. Proper controllers should override this method.
Copy link
Member

Choose a reason for hiding this comment

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

Refactor this into a SimpleWayPointController Class?
This would enforce that the function must be implemented.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Done

total_distance += std::sqrt( std::pow( trajectory[i].x - trajectory[i - 1].x, 2 ) +
std::pow( trajectory[i].y - trajectory[i - 1].y, 2 ) );
}
if ( total_distance <= 0.0 ) {
Copy link
Member

Choose a reason for hiding this comment

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

Not sure if this is valid. E.g a trajectory might only attempt to rotate the base.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Added consideration for change in headings

success = success && command_interfaces_[1].set_value( cmd.angual_vel_cmd ); // angular velocity
}

// Implement command setting logic here
Copy link
Member

Choose a reason for hiding this comment

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

?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Removed deprecated comment

}

controller_interface::return_type
WaypointControllerBase::update( const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/ )
Copy link
Member

Choose a reason for hiding this comment

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

Not sure if this applies to all controllers. I guess the base controllers themself should track their current goal. Also, the goal completion differs between intermediate and final waypoints.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Added a boolean parameter to the check goal completion function. Should this also apply to the computed Commands? Then each controller can adjust their strategy using this information

…letetion function. Controllers override this function to implement specific behavior when completing the final goal in the trajectory. Refactored computeCommand simple implementation into new controller class
@Joschi3 Joschi3 self-requested a review February 19, 2026 08:58
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.

2 participants