-
Notifications
You must be signed in to change notification settings - Fork 5
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
Teo vector verifcation #177
Open
taschnell
wants to merge
14
commits into
main
Choose a base branch
from
teo_vector_verifcation
base: main
Could not load branches
Branch not found: {{ refName }}
Loading
Could not load tags
Nothing to show
Loading
Are you sure you want to change the base?
Some commits from the old base branch may be removed from the timeline,
and old review comments may become outdated.
Open
Changes from 4 commits
Commits
Show all changes
14 commits
Select commit
Hold shift + click to select a range
2c00a2c
New Thrustverify.py, added math mod and hardcode configs to thrust.py
taschnell 5eedf6c
fixed TEO's mistakes
liamgilligan f6d0eb5
documentation update
taschnell 30e9714
Remove Unessecary code
taschnell 757736b
FIxed Linear Vector Caculation, need to update angular vector
taschnell 8bce7db
style(thrustverify): Config matrix grid spacing
OrionOth 903bd0e
style(thrust): Config matrix grid spacing
OrionOth 61c1f87
Updated Motor Configuration in Kinematics to encode torque, not posit…
liamgilligan 8d656d5
Removed debugging print statement
liamgilligan 580c84d
Removed unused math import
liamgilligan 8ce4b25
Updated motor configuration in Thrust Verification node to use correc…
liamgilligan e8ffd0c
Renamed Motor Configuration matrix to for consistency and made it a …
liamgilligan b4b1c69
Removed numpy import
liamgilligan df1b21a
Updated Thrust Verification to publish a Twist message instead of a F…
liamgilligan File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,79 @@ | ||
''' | ||
thrustverify.py | ||
|
||
Calculate predicted thrust and angular vector based on motor status and output it on /drive/predict | ||
|
||
Copyright (C) 2022-2023 Cabrillo Robotics Club | ||
|
||
This program is free software: you can redistribute it and/or modify | ||
it under the terms of the GNU Affero General Public License as published by | ||
the Free Software Foundation, either version 3 of the License, or | ||
(at your option) any later version. | ||
|
||
This program is distributed in the hope that it will be useful, | ||
but WITHOUT ANY WARRANTY; without even the implied warranty of | ||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the | ||
GNU Affero General Public License for more details. | ||
|
||
You should have received a copy of the GNU Affero General Public License | ||
along with this program. If not, see <https://www.gnu.org/licenses/>. | ||
|
||
Cabrillo Robotics Club | ||
6500 Soquel Drive Aptos, CA 95003 | ||
cabrillorobotics@gmail.com | ||
''' | ||
import sys | ||
|
||
import rclpy | ||
|
||
from rclpy.node import Node | ||
|
||
from geometry_msgs.msg import Twist | ||
from std_msgs.msg import Float32MultiArray | ||
|
||
import numpy as np | ||
|
||
class ThrustVerify(Node): | ||
"""Caculates expected input, based on current motor status""" | ||
|
||
def __init__(self): | ||
super().__init__('thrust') | ||
|
||
self.subscription = self.create_subscription(Float32MultiArray, 'drive/motors', self.motor_math, 10) | ||
self.vector_predict = self.create_publisher(Float32MultiArray, 'drive/predict', 10) | ||
|
||
def motor_math(self, msg): | ||
# motor 0-7 within list index | ||
motor_msg = msg | ||
|
||
config = [ | ||
[0, 0, 0, 0, 0.7071, 0.7071, -0.7071, -0.7071], | ||
[0, 0, 0, 0, -0.7071, 0.7071, -0.7071, 0.7071], | ||
[1, 1, 1, 1, 0, 0, 0, 0], | ||
[-.19, -.19, .19, .19, -.105, -.105, .105, .105], | ||
[-.12, .12, -.12, .12, -.15, .15, -.15, .15], | ||
[-.047,-.047,-.047, -.047, 0.038, 0.038, 0.038, 0.038] | ||
] | ||
|
||
# Linear Thrust Vector | ||
x = config[0][0]*motor_msg.data[4] + config[0][1]*motor_msg.data[5] + config[0][2]*motor_msg.data[6] + config[0][3]*motor_msg.data[7] | ||
y = config[1][0]*motor_msg.data[4] + config[1][1]*motor_msg.data[5] + config[1][2]*motor_msg.data[6] + config[1][3]*motor_msg.data[7] | ||
z = config[2][0]*motor_msg.data[0] + config[2][1]*motor_msg.data[1] + config[2][2]*motor_msg.data[2] + config[2][3]*motor_msg.data[3] | ||
|
||
# Angular Thrust Vector | ||
rx = config[3][0]*motor_msg.data[0] + config[3][1]*motor_msg.data[1] + config[3][2]*motor_msg.data[2] + config[3][3]*motor_msg.data[3] + config[3][4]*motor_msg.data[4] + config[3][5]*motor_msg.data[5] + config[3][6]*motor_msg.data[6] + config[3][7]*motor_msg.data[7] | ||
ry = config[4][0]*motor_msg.data[0] + config[4][1]*motor_msg.data[1] + config[4][2]*motor_msg.data[2] + config[4][3]*motor_msg.data[3] + config[4][4]*motor_msg.data[4] + config[4][5]*motor_msg.data[5] + config[4][6]*motor_msg.data[6] + config[4][7]*motor_msg.data[7] | ||
rz = config[5][0]*motor_msg.data[0] + config[5][1]*motor_msg.data[1] + config[5][2]*motor_msg.data[2] + config[5][3]*motor_msg.data[3] + config[5][4]*motor_msg.data[4] + config[5][5]*motor_msg.data[5] + config[5][6]*motor_msg.data[6] + config[5][7]*motor_msg.data[7] | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This is basically unreadable, is it possible to do this in a clearer and more programmatic (rather than purely mathematical) fashion? |
||
|
||
predicted_vectors = Float32MultiArray() | ||
predicted_vectors.data = [x, y, z, rx, ry, rz] | ||
|
||
self.vector_predict.publish(predicted_vectors) | ||
|
||
def main(args=None): | ||
rclpy.init(args=args) | ||
rclpy.spin(ThrustVerify()) | ||
rclpy.shutdown() | ||
|
||
if __name__ == '__main__': | ||
main(sys.argv) |
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Can you add a brief code comment describing what exactly this is, and how we got it? We can save specifics for markdown documentation (should probably write that too!)
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
These latest changes (757736b, 8bce7db), while they do help, don't particularly resolve describing what
config
is exactly. It's good you are describing the components of it, however.