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

Update to Foxy Fitzroy #2

Merged
merged 26 commits into from
May 28, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
26 commits
Select commit Hold shift + click to select a range
9d04f48
Initial commit
AndyZe May 25, 2018
4edc741
Merge branch 'master' of https://github.com/UTNuclearRoboticsPublic/pid
AndyZe May 25, 2018
aaabcfd
Setpoint node is done.
AndyZe May 25, 2018
97f1ebe
Adjusting file structure.
AndyZe May 28, 2018
89b7c55
Getting into the meat of code migration.
AndyZe May 28, 2018
f16b4bb
The meat of pid.cpp compiles but it does not spin correctly.
AndyZe May 29, 2018
5c532a8
Fixed the spinning issue. Controller node is functional.
AndyZe May 30, 2018
83422ca
It works! At a basic level.
AndyZe May 30, 2018
172c2e3
Adding a launch file and minor cleanup.
AndyZe May 30, 2018
6ab57b0
Trying to fix readme format.
AndyZe May 30, 2018
d6eabad
Setting topic names up for configuration, debug on PID parameters.
AndyZe May 30, 2018
7c4b868
Setting version number for initial release.
AndyZe May 30, 2018
77fa3c1
Correcting the tag.
AndyZe May 30, 2018
be9122e
Updating version
AndyZe May 30, 2018
290a90c
Re-write to use newer ROS2 launch file structure
bdholt1 May 18, 2021
9ecd8fb
Update to Foxy QoS profile
bdholt1 May 18, 2021
cb4a958
Replace lambda functions with member functions
bdholt1 May 18, 2021
42c59e0
Add newlines at end of files
bdholt1 May 18, 2021
be7b529
make control_effort callback private
bdholt1 May 18, 2021
d8438e6
Use ROS2 parameter mechanism for PID variables
bdholt1 May 18, 2021
fa78acc
Log callbacks under debug mode
bdholt1 May 18, 2021
bb6edcd
Do not ROS QoS profile - for some reason data isn't making it through…
bdholt1 May 18, 2021
774bf1e
Use 2 space indentation
bdholt1 May 18, 2021
c4d2467
fixed typo in comment
bdholt1 Jun 17, 2021
b300867
exposed angle_error and pid_enabled parameters
bdholt1 Jun 17, 2021
c966e9b
Merge branch 'foxy' into foxy
bdholt1 Jun 22, 2021
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
9 changes: 6 additions & 3 deletions include/pid/pid.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,13 +14,15 @@ namespace pid_ns
class PID : public rclcpp::Node
{
public:
explicit PID(double Kp, double Ki, double Kd);
explicit PID();
void doCalcs();

// Primary output variable
double control_effort_ = 0;

private:
void state_callback(const std_msgs::msg::Float64::SharedPtr msg);
void setpoint_callback(const std_msgs::msg::Float64::SharedPtr msg);
void printParameters();
bool validateParameters();

Expand All @@ -39,7 +41,7 @@ class PID : public rclcpp::Node
// PID gains
double Kp_ = 0, Ki_ = 0, Kd_ = 0;

// Parameters for error calc. with disconinuous input
// Parameters for error calc. with discontinuous input
bool angle_error_ = false;
double angle_wrap_ = 2.0 * 3.14159;

Expand Down Expand Up @@ -94,4 +96,5 @@ class PID : public rclcpp::Node
};
} // end pid namespace

#endif

#endif
46 changes: 20 additions & 26 deletions launch/servo_sim.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,30 +36,24 @@
##
###############################################################################

from launch.exit_handler import default_exit_handler, restart_exit_handler
from ros2run.api import get_executable_path
from launch import LaunchDescription
from launch_ros.actions import Node


def launch(launch_descriptor, argv):
ld = launch_descriptor
package = 'pid'
ld.add_process(
cmd=[get_executable_path(package_name=package, executable_name='controller')],
name='controller',
exit_handler=restart_exit_handler,
)
package = 'pid'
ld.add_process(
cmd=[get_executable_path(package_name=package, executable_name='setpoint')],
name='setpoint',
exit_handler=restart_exit_handler,
)
package = 'pid'
ld.add_process(
cmd=[get_executable_path(package_name=package, executable_name='servo_sim')],
name='servo_sim',
# The joy node is required, die if it dies
exit_handler=restart_exit_handler,
)

return ld
def generate_launch_description():
return LaunchDescription([
Node(
package='pid',
executable='controller',
name='controller'
),
Node(
package='pid',
executable='setpoint',
name='setpoint'
),
Node(
package='pid',
executable='servo_sim',
name='servo_sim'
)
])
2 changes: 1 addition & 1 deletion src/pid/controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ int main(int argc, char * argv[])
rclcpp::init(argc, argv);

// Create the PID node.
auto my_pid = std::make_shared<pid_ns::PID>(5, 0.1, 0.1);
auto my_pid = std::make_shared<pid_ns::PID>();

// Respond to inputs until shut down
// TODO: make this rate configurable
Expand Down
78 changes: 47 additions & 31 deletions src/pid/pid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,49 +41,54 @@
#include <pid/pid.h>

using namespace pid_ns;
using std::placeholders::_1;

PID::PID(double Kp, double Ki, double Kd):
PID::PID():
Node("controller"), delta_t_(0, 0)
{
// Callbacks for incoming state and setpoint messages
auto state_callback =
[this](const std_msgs::msg::Float64::SharedPtr msg) -> void
{
plant_state_ = msg-> data;
RCLCPP_INFO(this->get_logger(), "State: [%f]", plant_state_)

new_state_or_setpt_ = true;
};

auto setpoint_callback =
[this](const std_msgs::msg::Float64::SharedPtr msg) -> void
{
setpoint_ = msg->data;
RCLCPP_INFO(this->get_logger(), "Setpoint: [%f]", setpoint_)

new_state_or_setpt_ = true;
};

state_sub_ = create_subscription<std_msgs::msg::Float64>(topic_from_plant_, state_callback);
setpoint_sub_ = create_subscription<std_msgs::msg::Float64>(setpoint_topic_, setpoint_callback);
state_sub_ = this->create_subscription<std_msgs::msg::Float64>(topic_from_plant_, 10, std::bind(&PID::state_callback, this, _1));
setpoint_sub_ = this->create_subscription<std_msgs::msg::Float64>(setpoint_topic_, 10, std::bind(&PID::setpoint_callback, this, _1));

// Create a publisher with a custom Quality of Service profile.
rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
custom_qos_profile.depth = 7;
control_effort_pub_ = this->create_publisher<std_msgs::msg::Float64>(topic_from_controller_, custom_qos_profile);

// TODO: get these parameters from server,
// along with the other configurable params (cutoff_frequency_, etc.)
Kp_ = Kp;
Ki_ = Ki;
Kd_ = Kd;
// rclcpp::QoS custom_qos_profile(rclcpp::KeepLast(7), rmw_qos_profile_sensor_data);
control_effort_pub_ = this->create_publisher<std_msgs::msg::Float64>(topic_from_controller_, 10);

// Declare parameters
this->declare_parameter<double>("Kp", 1.0);
this->declare_parameter<double>("Ki", 0.0);
this->declare_parameter<double>("Kd", 0.0);
this->declare_parameter<double>("lower_limit", -1000.0);
this->declare_parameter<double>("upper_limit", 1000.0);
this->declare_parameter<double>("windup_limit", -1000.0);
this->declare_parameter<double>("cutoff_frequency", -1.0);
this->declare_parameter<bool>("angle_error", false);
this->declare_parameter<bool>("pid_enabled", true);

printParameters();

if (not validateParameters())
std::cout << "Error: invalid parameter\n";
}


// Callbacks for incoming state message
void PID::state_callback(const std_msgs::msg::Float64::SharedPtr msg)
{
plant_state_ = msg->data;
RCLCPP_DEBUG(this->get_logger(), "State: [%f]", plant_state_);

new_state_or_setpt_ = true;
}

void PID::setpoint_callback(const std_msgs::msg::Float64::SharedPtr msg)
{
setpoint_ = msg->data;
RCLCPP_DEBUG(this->get_logger(), "Setpoint: [%f]", setpoint_);

new_state_or_setpt_ = true;
}

void PID::printParameters()
{
std::cout << std::endl << "PID PARAMETERS" << std::endl << "-----------------------------------------" << std::endl;
Expand Down Expand Up @@ -120,6 +125,17 @@ void PID::doCalcs()
// Do fresh calcs if knowledge of the system has changed.
if (new_state_or_setpt_)
{
// Get parameters from the server
this->get_parameter("Kp", Kp_);
this->get_parameter("Ki", Ki_);
this->get_parameter("Kd", Kd_);
this->get_parameter("lower_limit", lower_limit_);
this->get_parameter("upper_limit", upper_limit_);
this->get_parameter("windup_limit", windup_limit_);
this->get_parameter("cutoff_frequency", cutoff_frequency_);
this->get_parameter("angle_error", angle_error_);
this->get_parameter("pid_enabled", pid_enabled_);

if (!((Kp_ <= 0. && Ki_ <= 0. && Kd_ <= 0.) ||
(Kp_ >= 0. && Ki_ >= 0. && Kd_ >= 0.))) // All 3 gains should have the same sign
{
Expand Down Expand Up @@ -236,4 +252,4 @@ void PID::doCalcs()
error_integral_ = 0.0;

new_state_or_setpt_ = false;
}
}
30 changes: 15 additions & 15 deletions src/pid/servo_sim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@
#include "rcutils/cmdline_parser.h"

#include "std_msgs/msg/float64.hpp"
using std::placeholders::_1;

void print_usage()
{
Expand All @@ -62,21 +63,13 @@ class ServoSim : public rclcpp::Node
explicit ServoSim()
: Node("servo_sim"), delta_t_(0, 0)
{
state_msg_ = std::make_shared<std_msgs::msg::Float64>();
state_msg_ = std_msgs::msg::Float64();

// Create a publisher with a custom Quality of Service profile.
rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
custom_qos_profile.depth = 7;
state_pub_ = this->create_publisher<std_msgs::msg::Float64>("state", custom_qos_profile);
// rclcpp::QoS custom_qos_profile(rclcpp::KeepLast(7), rmw_qos_profile_sensor_data);
state_pub_ = this->create_publisher<std_msgs::msg::Float64>("state", 10);

// Callback for incoming control_effort messages
auto control_effort_callback =
[this](const std_msgs::msg::Float64::SharedPtr msg) -> void
{
control_effort_ = msg-> data;
};

control_effort_sub_ = create_subscription<std_msgs::msg::Float64>("control_effort", control_effort_callback);
control_effort_sub_ = this->create_subscription<std_msgs::msg::Float64>("control_effort", 10, std::bind(&ServoSim::control_effort_callback, this, _1));

prev_time_ = this->now();
}
Expand All @@ -90,13 +83,20 @@ class ServoSim : public rclcpp::Node
acceleration_ = ((Kv_ * (control_effort_ - (Kbackemf_ * speed_)) + decel_force_) / mass_); // a = F/m
speed_ = speed_ + (acceleration_ * delta_t_.nanoseconds()/1e9);
displacement_ = displacement_ + speed_ * delta_t_.nanoseconds()/1e9;
state_msg_->data = displacement_;

state_msg_.data = displacement_;
state_pub_->publish(state_msg_);
}

private:
std::shared_ptr<std_msgs::msg::Float64> state_msg_;
// Callback for incoming control_effort messages
void control_effort_callback(const std_msgs::msg::Float64::SharedPtr msg)
{
control_effort_ = msg->data;
RCLCPP_DEBUG(this->get_logger(), "control effort: [%f]", control_effort_);
}

std_msgs::msg::Float64 state_msg_;
rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr state_pub_;
rclcpp::Subscription<std_msgs::msg::Float64>::SharedPtr control_effort_sub_;
double control_effort_ = 0;
Expand Down
23 changes: 10 additions & 13 deletions src/pid/setpoint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,20 +63,11 @@ class Setpoint : public rclcpp::Node
explicit Setpoint()
: Node("setpoint")
{
msg_ = std::make_shared<std_msgs::msg::Float64>();

// Create a function for when messages are to be sent.
auto publish_message =
[this](double& setpoint) -> void
{
msg_->data = setpoint;
pub_->publish(msg_);
};
msg_ = std_msgs::msg::Float64();

// Create a publisher with a custom Quality of Service profile.
rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
custom_qos_profile.depth = 7;
pub_ = this->create_publisher<std_msgs::msg::Float64>("setpoint", custom_qos_profile);
// rclcpp::QoS custom_qos_profile(rclcpp::KeepLast(7), rmw_qos_profile_sensor_data);
pub_ = this->create_publisher<std_msgs::msg::Float64>("setpoint", 10);

// Negate the setpoint every 5 seconds
rclcpp::Rate loop_rate(0.2);
Expand All @@ -91,8 +82,14 @@ class Setpoint : public rclcpp::Node
}
}

void publish_message(double& setpoint)
{
msg_.data = setpoint;
pub_->publish(msg_);
}

private:
std::shared_ptr<std_msgs::msg::Float64> msg_;
std_msgs::msg::Float64 msg_;
rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr pub_;
};

Expand Down