-
Notifications
You must be signed in to change notification settings - Fork 1
Expand file tree
/
Copy pathVelocityController.py
More file actions
58 lines (49 loc) · 1.61 KB
/
VelocityController.py
File metadata and controls
58 lines (49 loc) · 1.61 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
"""
testing offboard positon control with a simple takeoff script
"""
import rospy
from mavros_msgs.msg import State
from geometry_msgs.msg import PoseStamped, Pose, Point, Quaternion, Vector3, Twist, TwistStamped
import math
import numpy
from std_msgs.msg import Header
from PID import PID
class VelocityController:
target = PoseStamped()
output = TwistStamped()
def __init__(self):
self.X = PID()
self.Y = PID()
self.Z = PID()
self.lastTime = rospy.get_time()
self.target = None
def setTarget(self, target):
self.target = target
def update(self, state):
if (self.target is None):
rospy.logwarn("Target position for velocity controller is none.")
return None
# simplify variables a bit
time = state.header.stamp.to_sec()
position = state.pose.position
orientation = state.pose.orientation
# create output structure
output = TwistStamped()
output.header = state.header
# output velocities
linear = Vector3()
angular = Vector3()
# Control in X vel
linear.x = self.X.update(self.target.position.x, position.x, time)
# Control in Y vel
linear.y = self.Y.update(self.target.position.y, position.y, time)
# Control in Z vel
linear.z = self.Z.update(self.target.position.z, position.z, time)
# Control yaw (no x, y angular)
# TODO
output.twist = Twist()
output.twist.linear = linear
return output
def stop(self):
setTarget(self.current)
update(self.current)