diff --git a/launch/step_5.launch.py b/launch/step_5.launch.py new file mode 100644 index 0000000000000000000000000000000000000000..686110f5a5b4eb0019ffcb49b8df53ff6f5a67f6 --- /dev/null +++ b/launch/step_5.launch.py @@ -0,0 +1,24 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +from launch.actions import ExecuteProcess + + +def generate_launch_description(): + return LaunchDescription([ + Node( + package='turtlesim', + namespace='', + executable='turtlesim_node', + name='sim' + ), + Node( + package='lesson_05', + namespace='', + executable='step_5', + name='square' + ), + ExecuteProcess( + cmd=[['rqt']], + shell=False + ), + ]) diff --git a/lesson_05/step_5.py b/lesson_05/step_5.py new file mode 100644 index 0000000000000000000000000000000000000000..b83522fc1bf6a4e30c928ce6fe0bc9fd499a73e4 --- /dev/null +++ b/lesson_05/step_5.py @@ -0,0 +1,74 @@ +import rclpy +from rclpy.node import Node + +from geometry_msgs.msg import Twist +from turtlesim.msg import Pose +import math + +class PID: + def __init__(self, i_max = 0.0, i_min = 0.0, i_gain = 0.0, p_gain = 0.0, d_gain = 0.0,): + self.iMax = i_max # Maximum and minimum allowable integrator state + self.iMin = i_min + self.iGain = i_gain # integral gain + self.pGain = p_gain # proportional gain + self.dGain = d_gain # derivative gain + + self.dState = 0.0 # Last position input + self.iState = 0.0 # Integrator state + + def update_PID(self, error, position): + pTerm = self.pGain * error # calculate the proportional term + self.iState += error # calculate the integral state with appropriate limiting + if self.iState > self.iMax: + self.iState = self.iMax + elif self.iState < self.iMin: + self.iState = self.iMin + + iTerm = self.iGain * self.iState # calculate the integral term + dTerm = self.dGain * (position - self.dState) + self.dState = position + + return pTerm + iTerm - dTerm + +def angle_diff(a1, a2): + a = a1-a2 + return (a+math.pi)%(2*math.pi)-math.pi + + +class RurMover(Node): + def __init__(self): + super().__init__('minimal_publisher') + self.publisher_twist = self.create_publisher(Twist, 'turtle1/cmd_vel', 10) + self.pose_subscriber = self.create_subscription(Pose, 'turtle1/pose', self.pose_callback, 10) + self.desired_heading = - math.pi / 2 + self.SIDE_TIME = 5.0 + self.LINEAR_SPEED = 0.5 + self.timer = self.create_timer(self.SIDE_TIME, self.pub_timer_callback) + self.PID = PID() + + def pose_callback(self, msg): + self.get_logger().info('Current heading: "%f"' % msg.theta) + self.get_logger().info('Setpoint: "%f"' % self.desired_heading) + msg_pub = Twist() + msg_pub.linear.x = self.LINEAR_SPEED + error = angle_diff(self.desired_heading, msg.theta) + msg_pub.angular.z = self.PID.update_PID(error, msg.theta) + self.publisher_twist.publish(msg_pub) + + def pub_timer_callback(self): + self.desired_heading += math.pi / 2 + self.desired_heading %= 2 * math.pi + self.get_logger().info('New angle setpoint: "%f"' % self.desired_heading) + +def main(args=None): + rclpy.init(args=args) + + mover = RurMover() + + rclpy.spin(mover) + + mover.destroy_node() + rclpy.shutdown() + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/setup.py b/setup.py index 0e83277e26896894fdb28dc65870d33952f3406f..223a33c99200d7125ee8f755d7df89d8e60ceb79 100644 --- a/setup.py +++ b/setup.py @@ -27,6 +27,7 @@ setup( 'step_2 = lesson_05.step_2:main', 'step_3 = lesson_05.step_3:main', 'step_4 = lesson_05.step_4:main', + 'step_5 = lesson_05.step_5:main', ], }, )