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

Fix Code Style On pid_error #2329

Merged
merged 1 commit into from
Jan 29, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 6 additions & 7 deletions soccer/src/soccer/control/motion_control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,11 +7,9 @@
#include <rj_geometry/util.hpp>
#include <rj_utils/logging.hpp>


#include "game_state.hpp"
#include "planning/instant.hpp"


namespace control {

using planning::RobotInstant;
Expand Down Expand Up @@ -77,10 +75,12 @@ MotionControl::MotionControl(int shell_id, rclcpp::Node* node)
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);
error_y_pub_ = node->create_publisher<std_msgs::msg::Float64>("motion_control/pose_error_y", 10);
error_heading_pub_ = node->create_publisher<std_msgs::msg::Float64>("motion_control/pose_error_heading", 10);

error_x_pub_ =
node->create_publisher<std_msgs::msg::Float64>("motion_control/pose_error_x", 10);
error_y_pub_ =
node->create_publisher<std_msgs::msg::Float64>("motion_control/pose_error_y", 10);
error_heading_pub_ =
node->create_publisher<std_msgs::msg::Float64>("motion_control/pose_error_heading", 10);
}

void MotionControl::run(const RobotState& state, const planning::Trajectory& trajectory,
Expand Down Expand Up @@ -144,7 +144,6 @@ void MotionControl::run(const RobotState& state, const planning::Trajectory& tra
std_msgs::msg::Float64 error_heading_msg;
error_heading_msg.data = error.heading();
error_heading_pub_->publish(error_heading_msg);


correction = Twist(position_x_controller_.run(static_cast<float>(error.position().x())),
position_y_controller_.run(static_cast<float>(error.position().y())),
Expand Down
6 changes: 3 additions & 3 deletions soccer/src/soccer/control/motion_control.hpp
Original file line number Diff line number Diff line change
@@ -1,20 +1,20 @@
#pragma once

#include <rclcpp/rclcpp.hpp>

#include <context.hpp>
#include <rj_common/time.hpp>
#include <rj_constants/topic_names.hpp>
#include <rj_geometry/point.hpp>
#include <rj_param_utils/param.hpp>
#include <std_msgs/msg/float64.hpp>

#include "control/motion_setpoint.hpp"
#include "game_state.hpp"
#include "ros_debug_drawer.hpp"

#include <rc-fshare/pid.hpp>

#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/float64.hpp>

namespace control {

DECLARE_FLOAT64(params::kMotionControlParamModule, max_acceleration);
Expand Down