From 276afbb934fa19510956ec19ac4483720a9ed4da Mon Sep 17 00:00:00 2001 From: astik <41.astiksrivastava@gmail.com> Date: Tue, 7 May 2024 12:41:07 +0530 Subject: [PATCH] aggressive differential flatness controller --- Tools/ros2/differential_flatness/LICENSE | 202 ++++++++++ .../differential_flatness/__init__.py | 0 .../differential_flatness/config.py | 9 + .../differential_flatness/df_plotting.py | 41 ++ .../differential_flatness.py | 360 ++++++++++++++++++ .../differential_flatness/trajectory.py | 269 +++++++++++++ .../differential_flatness/waypoints.py | 35 ++ Tools/ros2/differential_flatness/package.xml | 24 ++ .../resource/differential_flatness | 0 Tools/ros2/differential_flatness/setup.cfg | 4 + Tools/ros2/differential_flatness/setup.py | 27 ++ .../test/test_copyright.py | 25 ++ .../differential_flatness/test/test_flake8.py | 25 ++ .../differential_flatness/test/test_pep257.py | 23 ++ 14 files changed, 1044 insertions(+) create mode 100644 Tools/ros2/differential_flatness/LICENSE create mode 100644 Tools/ros2/differential_flatness/differential_flatness/__init__.py create mode 100644 Tools/ros2/differential_flatness/differential_flatness/config.py create mode 100644 Tools/ros2/differential_flatness/differential_flatness/df_plotting.py create mode 100644 Tools/ros2/differential_flatness/differential_flatness/differential_flatness.py create mode 100644 Tools/ros2/differential_flatness/differential_flatness/trajectory.py create mode 100644 Tools/ros2/differential_flatness/differential_flatness/waypoints.py create mode 100644 Tools/ros2/differential_flatness/package.xml create mode 100644 Tools/ros2/differential_flatness/resource/differential_flatness create mode 100644 Tools/ros2/differential_flatness/setup.cfg create mode 100644 Tools/ros2/differential_flatness/setup.py create mode 100644 Tools/ros2/differential_flatness/test/test_copyright.py create mode 100644 Tools/ros2/differential_flatness/test/test_flake8.py create mode 100644 Tools/ros2/differential_flatness/test/test_pep257.py diff --git a/Tools/ros2/differential_flatness/LICENSE b/Tools/ros2/differential_flatness/LICENSE new file mode 100644 index 00000000000000..d645695673349e --- /dev/null +++ b/Tools/ros2/differential_flatness/LICENSE @@ -0,0 +1,202 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. diff --git a/Tools/ros2/differential_flatness/differential_flatness/__init__.py b/Tools/ros2/differential_flatness/differential_flatness/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/Tools/ros2/differential_flatness/differential_flatness/config.py b/Tools/ros2/differential_flatness/differential_flatness/config.py new file mode 100644 index 00000000000000..c947e27f316500 --- /dev/null +++ b/Tools/ros2/differential_flatness/differential_flatness/config.py @@ -0,0 +1,9 @@ +# Select Orientation of Quadcopter and Reference Frame +# --------------------------- +# "NED" for front-right-down (frd) and North-East-Down +# "ENU" for front-left-up (flu) and East-North-Up +orient = "NED" +kp_xy = 0 +kp_z = 0 +kd_xy = 0 +kd_z = 0 diff --git a/Tools/ros2/differential_flatness/differential_flatness/df_plotting.py b/Tools/ros2/differential_flatness/differential_flatness/df_plotting.py new file mode 100644 index 00000000000000..327b5e59d5c02f --- /dev/null +++ b/Tools/ros2/differential_flatness/differential_flatness/df_plotting.py @@ -0,0 +1,41 @@ +import numpy as np +from scipy.spatial.transform import Rotation as R + +# Current orientation quaternion +quad_quat = np.array([1, 0, 0, 0]) + +# Desired acceleration vector (normalized) +des_accn = np.array([0, 1, 9.8]) + +# Define the desired yaw angle (assuming it's 0 for hovering) +yaw_sp = 0.0 + +# Calculate full desired quaternion qd_full +body_z = -des_accn / np.linalg.norm(des_accn) # In ENU frame +y_C = np.array([-np.sin(yaw_sp), np.cos(yaw_sp), 0.0]) +body_x = np.cross(y_C, body_z) +body_x = body_x / np.linalg.norm(body_x) +body_y = np.cross(body_z, body_x) +R_sp = np.array([body_x, body_y, body_z]).T +Rot = R.from_matrix(R_sp) +quat = Rot.as_quat() +qd_full = np.array([quat[3], quat[0], quat[1], quat[2]]) + +# Calculate quaternion error +e_z = quad_quat[1:4] +qe_red = np.zeros(4) +qe_red[0] = np.dot(e_z, des_accn) + np.sqrt((1 - np.dot(e_z, e_z)) * (1 - np.dot(des_accn, des_accn))) +qe_red[1:4] = np.cross(e_z, des_accn) +qe_red = qe_red / np.linalg.norm(qe_red) + +# Calculate reduced desired quaternion +qd_red = qe_red * quad_quat + +# Calculate mixed desired quaternion +q_mix = qd_full * np.sign(qd_full[0]) + +# Calculate resulting desired quaternion +yaw_w = 1.0 # Yaw control weight +qd = qd_red * np.array([np.cos(yaw_w * np.arccos(q_mix[0])), 0, 0, np.sin(yaw_w * np.arcsin(q_mix[3]))]) + +print("Resulting desired quaternion (qd):", qd) \ No newline at end of file diff --git a/Tools/ros2/differential_flatness/differential_flatness/differential_flatness.py b/Tools/ros2/differential_flatness/differential_flatness/differential_flatness.py new file mode 100644 index 00000000000000..674b53eef79623 --- /dev/null +++ b/Tools/ros2/differential_flatness/differential_flatness/differential_flatness.py @@ -0,0 +1,360 @@ +import rclpy +from rclpy.node import Node +from sensor_msgs.msg import Imu +from ardupilot_msgs.msg import AngularVelandAccn +from geometry_msgs.msg import Quaternion, Vector3, PoseStamped, TwistStamped +from .trajectory import Trajectory +import numpy as np +from numpy.linalg import norm +import math +from rclpy.qos import QoSProfile, QoSDurabilityPolicy, QoSReliabilityPolicy, QoSHistoryPolicy +from rclpy.executors import MultiThreadedExecutor +# import scipy.spatial.transform as sci +from scipy.spatial.transform import Rotation as R + +class IMUPublisherSubscriber(Node): + def __init__(self): + super().__init__('imu_publisher_subscriber') + self.publisher = self.create_publisher(AngularVelandAccn, '/ap/cmd_ang_goals', 10) + + self.pose_subscriber_ = self.create_subscription( + PoseStamped, '/ap/pose/filtered', self.pose_callback, 10) + + self.twist_subscriber_ = self.create_subscription( + TwistStamped, '/ap/twist/filtered', self.velocity_callback, 10) + + self.timer = self.create_timer(0.01,self.prepare_angular_vel_accn_message) + self.start_time = self.get_clock().now().nanoseconds + self.desPos = np.zeros(3) # Desired position (x, y, z) + self.desVel = np.zeros(3) # Desired velocity (xdot, ydot, zdot) + self.desAcc = np.zeros(3) # Desired acceleration (xdotdot, ydotdot, zdotdot) + self.desThr = np.zeros(3) # Desired thrust in N-E-D directions (or E-N-U, if selected) + self.desEul = np.zeros(3) # Desired orientation in the world frame (phi, theta, psi) + self.desPQR = np.zeros(3) # Desired angular velocity in the body frame (p, q, r) + self.yawFF = 0.0 # Desired yaw speed + self.desJerk = np.zeros(3) # Desired Jerk (xdotdotdot, ydotdotdot, zdotdotdot) + self.desSnap = np.zeros(3) # Desired Snap (xdotdotdotdot, ydotdotdotdot, zdotdotdotdot) + + self.local_pose = PoseStamped() + self.local_vel = TwistStamped() + self.gravity = np.array([0, 0, 9.81]) + + self.command_msg = AngularVelandAccn() + self.max_thrust = 19.8 + self.traj = Trajectory() + + + def pose_callback(self, msg): + self.local_pose = msg + self.get_logger().info('position x = {:.2f}, y = {:.2f}, z = {:.2f}'.format(self.local_pose.pose.position.x, self.local_pose.pose.position.y, self.local_pose.pose.position.z)) + + def velocity_callback(self, msg): + self.local_vel = msg + + + def calculate_trajectory(self): + current_time = self.get_clock().now().nanoseconds + # t = (current_time - self.start_time)/1e9 # converting from nanoseconds to seconds + # self.sDes = self.traj.desiredState(t,0.01) + # self.desPos = np.array([self.sDes[0], self.sDes[1], self.sDes[2]]) + # self.desVel = np.array([self.sDes[3], self.sDes[4], self.sDes[5]]) + # self.desAcc = np.array([self.sDes[6], self.sDes[7], self.sDes[8]]) + # self.desThr = self.sDes[9:12] + # self.desEul = self.sDes[12:15] + # self.desPQR = self.sDes[15:18] + # self.yawFF = self.sDes[18] + # self.desJerk = self.sDes[19:22] + # self.desSnap = self.sDes[22:25] + self.desPos = np.array([0, 0, 3]) + + def quat_mult(self,q, p): + # Extract scalar and vector parts + Q = np.array([[q[0], -q[1], -q[2], -q[3]], + [q[1], q[0], -q[3], q[2]], + [q[2], q[3], q[0], -q[1]], + [q[3], -q[2], q[1], q[0]]]) + return Q@p + + + def quaternion_from_rotation_matrix(self, R): + # Extract the values from R + q0 = np.sqrt(1 + R[0, 0] + R[1, 1] + R[2, 2]) / 2 + q1 = (R[2, 1] - R[1, 2]) / (4 * q0) + q2 = (R[0, 2] - R[2, 0]) / (4 * q0) + q3 = (R[1, 0] - R[0, 1]) / (4 * q0) + return np.array([q0, q1, q2, q3]) + + def RotToQuat(self,R): + + R11 = R[0, 0] + R12 = R[0, 1] + R13 = R[0, 2] + R21 = R[1, 0] + R22 = R[1, 1] + R23 = R[1, 2] + R31 = R[2, 0] + R32 = R[2, 1] + R33 = R[2, 2] + # From page 68 of MotionGenesis book + tr = R11 + R22 + R33 + + if tr > R11 and tr > R22 and tr > R33: + e0 = 0.5 * np.sqrt(1 + tr) + r = 0.25 / e0 + e1 = (R32 - R23) * r + e2 = (R13 - R31) * r + e3 = (R21 - R12) * r + elif R11 > R22 and R11 > R33: + e1 = 0.5 * np.sqrt(1 - tr + 2*R11) + r = 0.25 / e1 + e0 = (R32 - R23) * r + e2 = (R12 + R21) * r + e3 = (R13 + R31) * r + elif R22 > R33: + e2 = 0.5 * np.sqrt(1 - tr + 2*R22) + r = 0.25 / e2 + e0 = (R13 - R31) * r + e1 = (R12 + R21) * r + e3 = (R23 + R32) * r + else: + e3 = 0.5 * np.sqrt(1 - tr + 2*R33) + r = 0.25 / e3 + e0 = (R21 - R12) * r + e1 = (R13 + R31) * r + e2 = (R23 + R32) * r + + # e0,e1,e2,e3 = qw,qx,qy,qz + q = np.array([e0,e1,e2,e3]) + q = q*np.sign(e0) + + q = q/np.sqrt(np.sum(q[0]**2 + q[1]**2 + q[2]**2 + q[3]**2)) + + return q + + def quat2Dcm(self,q): + dcm = np.zeros([3,3]) + + dcm[0,0] = q[0]**2 + q[1]**2 - q[2]**2 - q[3]**2 + dcm[0,1] = 2.0*(q[1]*q[2] - q[0]*q[3]) + dcm[0,2] = 2.0*(q[1]*q[3] + q[0]*q[2]) + dcm[1,0] = 2.0*(q[1]*q[2] + q[0]*q[3]) + dcm[1,1] = q[0]**2 - q[1]**2 + q[2]**2 - q[3]**2 + dcm[1,2] = 2.0*(q[2]*q[3] - q[0]*q[1]) + dcm[2,0] = 2.0*(q[1]*q[3] - q[0]*q[2]) + dcm[2,1] = 2.0*(q[2]*q[3] + q[0]*q[1]) + dcm[2,2] = q[0]**2 - q[1]**2 - q[2]**2 + q[3]**2 + + return dcm + + def rotate_vector_by_quaternion(self,v, q): + q_conj = np.array([q[0], -q[1], -q[2], -q[3]]) + v_quat = np.array([0] + list(v)) + return self.quat_mult(self.quat_mult(q, v_quat), q_conj)[1:] + + def normalize_vector(self, v): + norm = np.linalg.norm(v) + if norm == 0: + return v + return v / norm + + + def acceleration_setpoint(self): + vel = self.current_velocity() + pos = self.current_position() + desired_pos = np.array([10, 5, -10]) + desired_vel = np.array([0, 0, 0]) + pos_error = desired_pos - pos + vel_error = desired_vel - vel + acc_sp = 5*pos_error + 4*vel_error + + return acc_sp + + def normalized_thrust_setpoint(self, des_accn): + current_orientation = self.current_orientation() + + body_z = np.array([0, 0, -1]) + + z_inertial = self.rotate_vector_by_quaternion(body_z,current_orientation) + + + des_thrust = np.dot(des_accn, z_inertial)/self.max_thrust + + if des_thrust > 1.0: + des_thrust = 1.0 + elif des_thrust < 0.0: + des_thrust = 0.0 + return des_thrust + + + def desired_orientation(self, des_accn): + # Create Full Desired Quaternion Based on Thrust Setpoint and Desired Yaw Angle + # --------------------------- + yaw_sp = 0.0 + # Desired body_z axis direction + des_accn = -self.normalize_vector(des_accn) + body_z = des_accn + # Vector of desired Yaw direction in XY plane, rotated by pi/2 (fake body_y axis) + + y_C = np.array([-math.sin(yaw_sp), math.cos(yaw_sp), 0.0]) + x_C = np.array([math.cos(yaw_sp), math.sin(yaw_sp), 0.0]) + + # Desired body_x axis direction + body_x = np.cross(y_C, des_accn) + body_x = self.normalize_vector(body_x) + # Desired body_y axis direction + body_y = np.cross(des_accn, body_x) + body_y = self.normalize_vector(body_y) + R_sp = np.array([body_x, body_y, body_z]).T + qd_full = self.RotToQuat(R_sp) + r = self.quat2Dcm(self.current_orientation()) + e_z1 = np.array([0, 0, -1]) + e_z = np.dot(r,e_z1) + self.get_logger().info('e_z: x: {:.2f} y: {:.2f} z: {:.2f}]'.format(e_z[0], e_z[1], e_z[2])) + e_z_d = -self.normalize_vector(des_accn) + qe_red = np.zeros(4) + qe_red[0] = np.dot(e_z, e_z_d) + math.sqrt(norm(e_z)**2 * norm(e_z_d)**2) + qe_red[1:4] = np.cross(e_z, e_z_d) + qe_red = self.normalize_vector(qe_red) + + # Reduced desired quaternion (reduced because it doesn't consider the desired Yaw angle) + self.qd_red = self.quat_mult(qe_red, self.current_orientation()) + + # Mixed desired quaternion (between reduced and full) and resulting desired quaternion qd + q_mix = self.quat_mult(self.quat_inverse(self.qd_red), qd_full) + q_mix = q_mix*np.sign(q_mix[0]) + q_mix[0] = np.clip(q_mix[0], -1.0, 1.0) + q_mix[3] = np.clip(q_mix[3], -1.0, 1.0) + qd = self.quat_mult(self.qd_red, np.array([np.cos(yaw_sp*np.arccos(q_mix[0])), 0, 0, np.sin(yaw_sp*np.arcsin(q_mix[3]))])) + + return qd + + def quat_inverse(self,quat): + qinv = np.array([quat[0], -quat[1], -quat[2], -quat[3]])/norm(quat) + return qinv + + def computeNominalReference(self): + des_acceleration = self.acceleration_setpoint() + des_orientation = self.desired_orientation(des_acceleration) + roll, pitch, yaw = self.quaternion_to_euler(des_orientation) + rollc, pitchc, yawc = self.quaternion_to_euler(self.current_orientation()) + + #self.get_logger().info('current attitude: r: {:.2f} p: {:.2f} y: {:.2f}]'.format(rollc, pitchc, yawc)) + self.get_logger().info('desired acceleration x = {:,.2f}, y = {:,.2f}, z = {:,.2f}'.format(des_acceleration[0], des_acceleration[1], des_acceleration[2])) + + body_x = self.rotate_vector_by_quaternion(np.array([1, 0, 0]), des_orientation) + body_y = self.rotate_vector_by_quaternion(np.array([0, 1, 0]), des_orientation) + body_z = self.rotate_vector_by_quaternion(np.array([0, 0, 1]), des_orientation) + + reference_heading = self.desEul[2] + q_heading = np.array([math.cos(reference_heading/2), 0, 0, math.sin(reference_heading/2)]) + x_C = self.rotate_vector_by_quaternion(np.array([1, 0, 0]), q_heading) + y_C = self.rotate_vector_by_quaternion(np.array([0, 1, 0]), q_heading) + + ref_acc = self.desAcc + self.gravity + pqr_sp = np.zeros(3) + pqr_dot_sp = np.zeros(3) + if(np.isclose(np.linalg.norm(ref_acc), 0)): + pqr_sp[0] = 0.0 + pqr_sp[0] = 0.0 + else: + pqr_sp[0] = -1/np.linalg.norm(ref_acc)*np.dot(body_y,self.desJerk) + pqr_sp[1] = 1/np.linalg.norm(ref_acc)*np.dot(body_x,self.desJerk) + if(np.isclose(np.linalg.norm(np.cross(y_C,body_z)), 0)): + pqr_sp[2] = 0.0 + else: + pqr_sp[2] = 1/np.linalg.norm(np.cross(y_C,body_z))*(self.yawFF*np.dot(x_C,body_x) + pqr_sp[1]*np.dot(y_C,body_z)) + #print("ang rate setpoint",pqr_sp) + thrust_dot = np.dot(body_z,self.desJerk) + if(np.isclose(np.linalg.norm(ref_acc), 0)): + pqr_dot_sp[0] = 0.0 + pqr_dot_sp[1] = 0.0 + else: + pqr_dot_sp[0] = -1/np.linalg.norm(ref_acc)*(np.dot(body_y,self.desSnap) + 2*thrust_dot*pqr_sp[0] - np.linalg.norm(ref_acc)*pqr_sp[1]*pqr_sp[2]) + pqr_dot_sp[1] = -1/np.linalg.norm(ref_acc)*(np.dot(body_x,self.desSnap) + 2*thrust_dot*pqr_sp[1] - np.linalg.norm(ref_acc)*pqr_sp[0]*pqr_sp[2]) + if(np.linalg.norm(np.cross(y_C,body_z)) < 0.7): + pqr_dot_sp[2] = 0.0 + else: + pqr_dot_sp[2] = 1/np.linalg.norm(np.cross(y_C,body_z))*(2*self.yawFF*pqr_sp[2]*np.dot(x_C,body_y) + - 2*self.yawFF*pqr_sp[1]*np.dot(x_C,body_z) + - pqr_sp[0]*pqr_sp[1]*np.dot(y_C,body_y) + - pqr_sp[0]*pqr_sp[2]*np.dot(y_C,body_z) + + pqr_dot_sp[1]*np.dot(y_C,body_z)) + + self.command_msg.angular_rate.x = 0.0 + self.command_msg.angular_rate.y = 0.0 + self.command_msg.angular_rate.z = 0.0 + + self.command_msg.angular_acceleration.x = pqr_dot_sp[0] + self.command_msg.angular_acceleration.y = pqr_dot_sp[1] + self.command_msg.angular_acceleration.z = pqr_dot_sp[2] + + + def prepare_angular_vel_accn_message(self): + # Prepare the AngularVelandAccn message + self.calculate_trajectory() + des_acc = self.acceleration_setpoint() + orientation = self.desired_orientation(des_acc) + thrust = self.normalized_thrust_setpoint(des_acc) + self.computeNominalReference() + self.command_msg.orientation = Quaternion(x = orientation[0], y = orientation[1], z = orientation[2], w = orientation[3]) + self.get_logger().info('desired orientation x = {:,.2f}, y = {:,.2f}, z = {:,.2f}, w = {:,.2f}'.format(orientation[0], orientation[1], orientation[2], orientation[3])) + + self.command_msg.thrust = thrust + # Publish the AngularVelandAccn message + self.publisher.publish(self.command_msg) + #self.get_logger().info('Published command Message, thrust = {:.2f}'.format(thrust)) + #self.get_logger().info('Published orientation Message, quaternion w = {:.2f}, x = {:.2f}, y = {:.2f}, z = {:.2f}'.format(orientation[0],orientation[1],orientation[2],orientation[3])) + + def quaternion_to_euler(self,quaternion): + """ + Convert a quaternion into Euler angles (roll, pitch, yaw) + roll is rotation around x in radians (counterclockwise) + pitch is rotation around y in radians (counterclockwise) + yaw is rotation around z in radians (counterclockwise) + """ + w = quaternion[0] + x = quaternion[1] + y = quaternion[2] + z = quaternion[3] + t0 = +2.0 * (w * x + y * z) + t1 = +1.0 - 2.0 * (x * x + y * y) + roll = math.atan2(t0, t1) + + t2 = +2.0 * (w * y - z * x) + t2 = +1.0 if t2 > +1.0 else t2 + t2 = -1.0 if t2 < -1.0 else t2 + pitch = math.asin(t2) + + t3 = +2.0 * (w * z + x * y) + t4 = +1.0 - 2.0 * (y * y + z * z) + yaw = math.atan2(t3, t4) + + return roll*180/math.pi, pitch*180/math.pi, yaw*180/math.pi + # from ENU to NED + def current_orientation(self): + q_transformation = np.array([1/math.sqrt(2), 0, 0, -1/math.sqrt(2)]) + q_received = np.array([self.local_pose.pose.orientation.w, self.local_pose.pose.orientation.x, self.local_pose.pose.orientation.y, self.local_pose.pose.orientation.z]) + q1 = self.quat_mult(q_received,q_transformation) + q2 = np.array([q1[0], q1[2], q1[1], -q1[3]]) + return q2 + # from ENU to NED + def current_position(self): + q2 = np.array([self.local_pose.pose.position.y, self.local_pose.pose.position.x, -self.local_pose.pose.position.z]) + return q2 + + def current_velocity(self): + q2 = np.array([self.local_vel.twist.linear.y, self.local_vel.twist.linear.x, -self.local_vel.twist.linear.z]) + return q2 + +def main(args=None): + rclpy.init(args=args) + imu_publisher_subscriber = IMUPublisherSubscriber() + executor = MultiThreadedExecutor() + executor.add_node(imu_publisher_subscriber) + executor.spin() + imu_publisher_subscriber.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/Tools/ros2/differential_flatness/differential_flatness/trajectory.py b/Tools/ros2/differential_flatness/differential_flatness/trajectory.py new file mode 100644 index 00000000000000..f16dbf254c6291 --- /dev/null +++ b/Tools/ros2/differential_flatness/differential_flatness/trajectory.py @@ -0,0 +1,269 @@ +# -*- coding: utf-8 -*- +""" +author: John Bass +email: john.bobzwik@gmail.com +license: MIT +Please feel free to use and modify this, but keep the above information. Thanks! +""" +# Functions get_poly_cc, minSomethingTraj, pos_waypoint_min are derived from Peter Huang's work: +# https://github.com/hbd730/quadcopter-simulation +# author: Peter Huang +# email: hbd730@gmail.com +# license: BSD +# Please feel free to use and modify this, but keep the above information. Thanks! + + + +import numpy as np +from numpy import pi +from numpy.linalg import norm +from .waypoints import makeWaypoints +from ardupilot_msgs.msg import AngularVelandAccn + +class Trajectory: + + def __init__(self): + #print("trajectory initialization") + self.averVel = 1 + + t_wps, wps, y_wps, v_wp = makeWaypoints() + self.t_wps = t_wps + self.wps = wps + self.y_wps = y_wps + self.v_wp = v_wp + + self.end_reached = 0 + + self.T_segment = np.diff(self.t_wps) + + if (self.averVel == 1): + distance_segment = self.wps[1:] - self.wps[:-1] + self.T_segment = np.sqrt(distance_segment[:,0]**2 + distance_segment[:,1]**2 + distance_segment[:,2]**2)/self.v_wp + self.t_wps = np.zeros(len(self.T_segment) + 1) + self.t_wps[1:] = np.cumsum(self.T_segment) + + self.deriv_order = 4 # Looking to minimize which derivative order (eg: Minimum velocity -> first order) + + # Calculate coefficients + self.coeff_x = minSomethingTraj(self.wps[:,0], self.T_segment, self.deriv_order) + self.coeff_y = minSomethingTraj(self.wps[:,1], self.T_segment, self.deriv_order) + self.coeff_z = minSomethingTraj(self.wps[:,2], self.T_segment, self.deriv_order) + + self.y_wps = np.zeros(len(self.t_wps)) + + # Get initial heading + self.current_heading = 0 + + # Initialize trajectory setpoint + self.desPos = np.zeros(3) # Desired position (x, y, z) + self.desVel = np.zeros(3) # Desired velocity (xdot, ydot, zdot) + self.desAcc = np.zeros(3) # Desired acceleration (xdotdot, ydotdot, zdotdot) + self.desThr = np.zeros(3) # Desired thrust in N-E-D directions (or E-N-U, if selected) + self.desEul = np.zeros(3) # Desired orientation in the world frame (phi, theta, psi) + self.desPQR = np.zeros(3) # Desired angular velocity in the body frame (p, q, r) + self.desYawRate = 0. # Desired yaw speed + self.desJerk = np.zeros(3) # Desired Jerk (xdotdotdot, ydotdotdot, zdotdotdot) + self.desSnap = np.zeros(3) # Desired Snap (xdotdotdotdot, ydotdotdotdot, zdotdotdotdot) + self.sDes = np.hstack((self.desPos, self.desVel, self.desAcc, self.desThr, self.desEul, self.desPQR, self.desYawRate, self.desJerk, self.desSnap)).astype(float) + + def desiredState(self, t, Ts): + #print("in desired state function") + self.desPos = np.zeros(3) # Desired position (x, y, z) + self.desVel = np.zeros(3) # Desired velocity (xdot, ydot, zdot) + self.desAcc = np.zeros(3) # Desired acceleration (xdotdot, ydotdot, zdotdot) + self.desThr = np.zeros(3) # Desired thrust in N-E-D directions (or E-N-U, if selected) + self.desEul = np.zeros(3) # Desired orientation in the world frame (phi, theta, psi) + self.desPQR = np.zeros(3) # Desired angular velocity in the body frame (p, q, r) + self.desYawRate = 0. # Desired yaw speed + self.desJerk = np.zeros(3) # Desired Jerk (xdotdotdot, ydotdotdot, zdotdotdot) + self.desSnap = np.zeros(3) # Desired Snap (xdotdotdotdot, ydotdotdotdot, zdotdotdotdot) + + + + + def pos_waypoint_min(): + #print("in waypoint min function") + """ The function takes known number of waypoints and time, then generates a + minimum velocity, acceleration, jerk or snap trajectory which goes through each waypoint. + The output is the desired state associated with the next waypoint for the time t. + """ + if not (len(self.t_wps) == self.wps.shape[0]): + raise Exception("Time array and waypoint array not the same size.") + + nb_coeff = self.deriv_order*2 + + # Hover at t=0 + if t == 0: + self.t_idx = 0 + self.desPos = self.wps[0,:] + # Stay hover at the last waypoint position + elif (t >= self.t_wps[-1]): + self.t_idx = -1 + self.desPos = self.wps[-1,:] + else: + self.t_idx = np.where(t <= self.t_wps)[0][0] - 1 + + # Scaled time (between 0 and duration of segment) + scale = (t - self.t_wps[self.t_idx]) + + # Which coefficients to use + start = nb_coeff * self.t_idx + end = nb_coeff * (self.t_idx + 1) + + # Set desired position, velocity and acceleration + t0 = get_poly_cc(nb_coeff, 0, scale) + self.desPos = np.array([self.coeff_x[start:end].dot(t0), self.coeff_y[start:end].dot(t0), self.coeff_z[start:end].dot(t0)]) + + t1 = get_poly_cc(nb_coeff, 1, scale) + self.desVel = np.array([self.coeff_x[start:end].dot(t1), self.coeff_y[start:end].dot(t1), self.coeff_z[start:end].dot(t1)]) + + t2 = get_poly_cc(nb_coeff, 2, scale) + self.desAcc = np.array([self.coeff_x[start:end].dot(t2), self.coeff_y[start:end].dot(t2), self.coeff_z[start:end].dot(t2)]) + + t3 = get_poly_cc(nb_coeff, 3, scale) + self.desJerk = np.array([self.coeff_x[start:end].dot(t3), self.coeff_y[start:end].dot(t3), self.coeff_z[start:end].dot(t3)]) + + t4 = get_poly_cc(nb_coeff, 4, scale) + self.desSnap = np.array([self.coeff_x[start:end].dot(t4), self.coeff_y[start:end].dot(t4), self.coeff_z[start:end].dot(t4)]) + + + def yaw_follow(): + #print("in yaw function") + if (t == 0) or (t >= self.t_wps[-1]): + self.desEul[2] = 0.0 + else: + # Calculate desired Yaw + self.desEul[2] = 0.0 + + # Dirty hack, detect when desEul[2] switches from -pi to pi (or vice-versa) and switch manualy current_heading + if (np.sign(self.desEul[2]) - np.sign(self.current_heading) and abs(self.desEul[2]-self.current_heading) >= 2*pi-0.1): + self.current_heading = self.current_heading + np.sign(self.desEul[2])*2*pi + + # Angle between current vector with the next heading vector + delta_psi = self.desEul[2] - self.current_heading + + # Set Yaw rate + self.desYawRate = delta_psi / Ts + + # Prepare next iteration + self.current_heading = self.desEul[2] + + # Set desired positions at every t_wps[i] + # Calculate a minimum velocity, acceleration, jerk or snap trajectory + pos_waypoint_min() + # Set desired yaw at every t_wps[i] + # Have the drone's heading match its desired velocity direction + yaw_follow() + + self.sDes = np.hstack((self.desPos, self.desVel, self.desAcc, self.desThr, self.desEul, self.desPQR, self.desYawRate, self.desJerk, self.desSnap)).astype(float) + #print("finishing desired state function", t) + + return self.sDes + + +def get_poly_cc(n, k, t): + """ This is a helper function to get the coeffitient of coefficient for n-th + order polynomial with k-th derivative at time t. + """ + assert (n > 0 and k >= 0), "order and derivative must be positive." + + cc = np.ones(n) + D = np.linspace(n-1, 0, n) + + for i in range(n): + for j in range(k): + cc[i] = cc[i] * D[i] + D[i] = D[i] - 1 + if D[i] == -1: + D[i] = 0 + + for i, c in enumerate(cc): + cc[i] = c * np.power(t, D[i]) + return cc + +def minSomethingTraj(waypoints, times, order): + #print("in mintraj function") + """ This function takes a list of desired waypoint i.e. [x0, x1, x2...xN] and + time, returns a [M*N,1] coeffitients matrix for the N+1 waypoints (N segments), + where M is the number of coefficients per segment and is equal to (order)*2. If one + desires to create a minimum velocity, order = 1. Minimum snap would be order = 4. + + 1.The Problem + Generate a full trajectory across N+1 waypoint is made of N polynomial line segment. + Each segment is defined as a (2*order-1)-th order polynomial defined as follow: + Minimum velocity: Pi = ai_0 + ai1*t + Minimum acceleration: Pi = ai_0 + ai1*t + ai2*t^2 + ai3*t^3 + Minimum jerk: Pi = ai_0 + ai1*t + ai2*t^2 + ai3*t^3 + ai4*t^4 + ai5*t^5 + Minimum snap: Pi = ai_0 + ai1*t + ai2*t^2 + ai3*t^3 + ai4*t^4 + ai5*t^5 + ai6*t^6 + ai7*t^7 + + Each polynomial has M unknown coefficients, thus we will have M*N unknown to + solve in total, so we need to come up with M*N constraints. + + 2.The constraints + In general, the constraints is a set of condition which define the initial + and final state, continuity between each piecewise function. This includes + specifying continuity in higher derivatives of the trajectory at the + intermediate waypoints. + + 3.Matrix Design + Since we have M*N unknown coefficients to solve, and if we are given M*N + equations(constraints), then the problem becomes solving a linear equation. + + A * Coeff = B + + Let's look at B matrix first, B matrix is simple because it is just some constants + on the right hand side of the equation. There are M*N constraints, + so B matrix will be [M*N, 1]. + + Coeff is the final output matrix consists of M*N elements. + Since B matrix is only one column, Coeff matrix must be [M*N, 1]. + + A matrix is tricky, we then can think of A matrix as a coeffient-coeffient matrix. + We are no longer looking at a particular polynomial Pi, but rather P1, P2...PN + as a whole. Since now our Coeff matrix is [M*N, 1], and B is [M*N, 1], thus + A matrix must have the form [M*N, M*N]. + + A = [A10 A11 ... A1M A20 A21 ... A2M ... AN0 AN1 ... ANM + ... + ] + + Each element in a row represents the coefficient of coeffient aij under + a certain constraint, where aij is the jth coeffient of Pi with i = 1...N, j = 0...(M-1). + """ + + n = len(waypoints) - 1 + nb_coeff = order*2 + + # initialize A, and B matrix + A = np.zeros([nb_coeff*n, nb_coeff*n]) + B = np.zeros(nb_coeff*n) + + # populate B matrix. + for i in range(n): + B[i] = waypoints[i] + B[i + n] = waypoints[i+1] + + # Constraint 1 - Starting position for every segment + for i in range(n): + A[i][nb_coeff*i:nb_coeff*(i+1)] = get_poly_cc(nb_coeff, 0, 0) + + # Constraint 2 - Ending position for every segment + for i in range(n): + A[i+n][nb_coeff*i:nb_coeff*(i+1)] = get_poly_cc(nb_coeff, 0, times[i]) + + # Constraint 3 - Starting position derivatives (up to order) are null + for k in range(1, order): + A[2*n+k-1][:nb_coeff] = get_poly_cc(nb_coeff, k, 0) + + # Constraint 4 - Ending position derivatives (up to order) are nullafter the 1967 and leading up to 1970, the PLO (Palestinian Liberation Organization) started acting like a Mafia inside Jordan. They began sending out their own armed thugs to charge protection money from Jordanian citizens as “taxes”. The PLO skirmished with Jordanian police and attempted to act as a state within a state, until in 1970 they actually tried to overthrow the Jordanian government. + for k in range(1, order): + A[2*n+(order-1)+k-1][-nb_coeff:] = get_poly_cc(nb_coeff, k, times[i]) + + # Constraint 5 - All derivatives are continuous at each waypint transition + for i in range(n-1): + for k in range(1, nb_coeff-1): + A[2*n+2*(order-1) + i*2*(order-1)+k-1][i*nb_coeff : (i*nb_coeff+nb_coeff*2)] = np.concatenate((get_poly_cc(nb_coeff, k, times[i]), -get_poly_cc(nb_coeff, k, 0))) + + # solve for the coefficients + Coeff = np.linalg.solve(A, B) + return Coeff \ No newline at end of file diff --git a/Tools/ros2/differential_flatness/differential_flatness/waypoints.py b/Tools/ros2/differential_flatness/differential_flatness/waypoints.py new file mode 100644 index 00000000000000..3add718b585b5d --- /dev/null +++ b/Tools/ros2/differential_flatness/differential_flatness/waypoints.py @@ -0,0 +1,35 @@ +# -*- coding: utf-8 -*- +""" +author: John Bass +email: john.bobzwik@gmail.com +license: MIT +Please feel free to use and modify this, but keep the above information. Thanks! +""" + +import numpy as np +from numpy import pi + +deg2rad = pi/180.0 + +def makeWaypoints(): + + v_average = 10 + + t_ini = 3 + t = np.array([5, 5, 5, 5]) + + wp_ini = np.array([0, 0, 0]) + wp = np.array([[0, 0, 10], + [0, 0, 20], + [0, 0, 30], + [0, 0, 40], + [0, 0, 50]]) + + yaw_ini = 0 + yaw = np.array([0, 0, 0, 0, 0]) + + t = np.hstack((t_ini, t)).astype(float) + wp = np.vstack((wp_ini, wp)).astype(float) + yaw = np.hstack((yaw_ini, yaw)).astype(float)*deg2rad + + return t, wp, yaw, v_average diff --git a/Tools/ros2/differential_flatness/package.xml b/Tools/ros2/differential_flatness/package.xml new file mode 100644 index 00000000000000..46a41c4c925089 --- /dev/null +++ b/Tools/ros2/differential_flatness/package.xml @@ -0,0 +1,24 @@ + + + + differential_flatness + 0.0.0 + TODO: Package description + astik + Apache-2.0 + + + rclpy + sensor_msgs + ardupilot_msgs + geometry_msgs + + + ament_lint_auto + ament_lint_common + python3-pytest + + + ament_python + + diff --git a/Tools/ros2/differential_flatness/resource/differential_flatness b/Tools/ros2/differential_flatness/resource/differential_flatness new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/Tools/ros2/differential_flatness/setup.cfg b/Tools/ros2/differential_flatness/setup.cfg new file mode 100644 index 00000000000000..fe19d4abf6c905 --- /dev/null +++ b/Tools/ros2/differential_flatness/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/differential_flatness +[install] +install_scripts=$base/lib/differential_flatness diff --git a/Tools/ros2/differential_flatness/setup.py b/Tools/ros2/differential_flatness/setup.py new file mode 100644 index 00000000000000..540c89f1f9baf8 --- /dev/null +++ b/Tools/ros2/differential_flatness/setup.py @@ -0,0 +1,27 @@ +from setuptools import find_packages, setup + +package_name = 'differential_flatness' + +setup( + name=package_name, + version='0.0.0', + packages=find_packages(exclude=['test']), + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + ], + entry_points={ + 'console_scripts': [ + 'commander = differential_flatness.differential_flatness:main', + 'commander_plotter = differential_flatness.df_plotting:main' + ], + }, + install_requires=['setuptools'], + zip_safe=True, + maintainer='astik', + maintainer_email='41.astiksrivastava@gmail.com', + description='TODO: Package description', + license='Apache-2.0', + tests_require=['pytest'], +) diff --git a/Tools/ros2/differential_flatness/test/test_copyright.py b/Tools/ros2/differential_flatness/test/test_copyright.py new file mode 100644 index 00000000000000..97a39196e84db9 --- /dev/null +++ b/Tools/ros2/differential_flatness/test/test_copyright.py @@ -0,0 +1,25 @@ +# Copyright 2015 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from ament_copyright.main import main +import pytest + + +# Remove the `skip` decorator once the source file(s) have a copyright header +@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.') +@pytest.mark.copyright +@pytest.mark.linter +def test_copyright(): + rc = main(argv=['.', 'test']) + assert rc == 0, 'Found errors' diff --git a/Tools/ros2/differential_flatness/test/test_flake8.py b/Tools/ros2/differential_flatness/test/test_flake8.py new file mode 100644 index 00000000000000..27ee1078ff077c --- /dev/null +++ b/Tools/ros2/differential_flatness/test/test_flake8.py @@ -0,0 +1,25 @@ +# Copyright 2017 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from ament_flake8.main import main_with_errors +import pytest + + +@pytest.mark.flake8 +@pytest.mark.linter +def test_flake8(): + rc, errors = main_with_errors(argv=[]) + assert rc == 0, \ + 'Found %d code style errors / warnings:\n' % len(errors) + \ + '\n'.join(errors) diff --git a/Tools/ros2/differential_flatness/test/test_pep257.py b/Tools/ros2/differential_flatness/test/test_pep257.py new file mode 100644 index 00000000000000..b234a3840f4c5b --- /dev/null +++ b/Tools/ros2/differential_flatness/test/test_pep257.py @@ -0,0 +1,23 @@ +# Copyright 2015 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from ament_pep257.main import main +import pytest + + +@pytest.mark.linter +@pytest.mark.pep257 +def test_pep257(): + rc = main(argv=['.', 'test']) + assert rc == 0, 'Found code style errors / warnings'