Conversation
|
| @@ -0,0 +1,9 @@ | |||
| geometry_msgs/Point[] waypoint_trajectory | |||
There was a problem hiding this comment.
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[]
There was a problem hiding this comment.
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 | |||
There was a problem hiding this comment.
Please provide a short overview of the msgs package.
There was a problem hiding this comment.
Also update the top-level readme to include the waypoint controller
| Waypoint() | ||
| { | ||
| x = 0.0; | ||
| y = 0.0; |
There was a problem hiding this comment.
What about the (final) orientation?
There was a problem hiding this comment.
Added headings to the waipoints
| geometry_msgs::msg::TransformStamped t; | ||
|
|
||
| try { | ||
| t = tf_buffer_->lookupTransform( "map", base_link_frame_, tf2::TimePointZero ); |
There was a problem hiding this comment.
Prefer not to hardcode any frames.
| std::pow( goal.y - current_pose.y, 2 ) ) <= goal_completion_tolerance_; | ||
| } | ||
|
|
||
| // Simple placeholder implementation for testing. Proper controllers should override this method. |
There was a problem hiding this comment.
Refactor this into a SimpleWayPointController Class?
This would enforce that the function must be implemented.
| 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 ) { |
There was a problem hiding this comment.
Not sure if this is valid. E.g a trajectory might only attempt to rotate the base.
There was a problem hiding this comment.
Added consideration for change in headings
| success = success && command_interfaces_[1].set_value( cmd.angual_vel_cmd ); // angular velocity | ||
| } | ||
|
|
||
| // Implement command setting logic here |
There was a problem hiding this comment.
Removed deprecated comment
| } | ||
|
|
||
| controller_interface::return_type | ||
| WaypointControllerBase::update( const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/ ) |
There was a problem hiding this comment.
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.
There was a problem hiding this comment.
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
No description provided.