Skip to content
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

PID Error Graphs #2328

Open
wants to merge 5 commits into
base: ros2
Choose a base branch
from
Open

PID Error Graphs #2328

wants to merge 5 commits into from

Conversation

Squid5678
Copy link
Contributor

Description

This PR enables you to view a real-time graph of the PID errors.

Associated / Resolved Issue

https://app.clickup.com/t/86b1vtz2u

Steps to Test

  1. Open a terminal window and start sim.
  2. Open another terminal window, source, and type in rqt.
  3. Click plugins --> visualization --> plot (note: if you want to view them
    all on one graph, that's fine. If you want to view translational/rotational separately,
    then you can repeat this step and open another plot).
  4. Under topic, type /motion_control/pose_error_x/data for x error, /motion_control/pose_error_y for y error, and /motion_control/pose_error_heading for heading error. Then, hit the + icon to add the measurement to the plot.
  5. observe.

@@ -95,6 +98,9 @@ class MotionControl {
rclcpp::Subscription<PlayState::Msg>::SharedPtr play_state_sub_;
rclcpp::Publisher<MotionSetpoint::Msg>::SharedPtr motion_setpoint_pub_;
rclcpp::Publisher<RobotState::Msg>::SharedPtr target_state_pub_;
rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr error_x_pub_;
rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr error_y_pub_;
rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr error_heading_pub_;
Copy link
Contributor

Choose a reason for hiding this comment

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

Great job! I appreciate your excellent use of ros2 topics

automated style fixes

Co-authored-by: Squid5678 <[email protected]>

std_msgs::msg::Float64 error_x_msg;
error_x_msg.data = error.position().x();
error_x_pub_->publish(error_x_msg);
Copy link
Contributor

Choose a reason for hiding this comment

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

Check if there are subscribers before publishing. This way, we're not using resources if no one is looking at the graph.

@@ -74,6 +74,13 @@ MotionControl::MotionControl(int shell_id, rclcpp::Node* node)
[this](PlayState::Msg::SharedPtr play_state_msg) { // NOLINT
play_state_ = rj_convert::convert_from_ros(*play_state_msg).state();
});

error_x_pub_ =
node->create_publisher<std_msgs::msg::Float64>("motion_control/pose_error_x", 10);
Copy link
Contributor

Choose a reason for hiding this comment

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

Let's prepend this name with debug (i.e. "debug/motion_control/pose_error_x"). Same for the below topics.

@@ -0,0 +1,12 @@
Metadata-Version: 2.1
Copy link
Contributor

Choose a reason for hiding this comment

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

Do we need to commit the egg info stuff?

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.

3 participants