5 from geometry_msgs.msg
import Twist,Vector3
21 w1 = math.cos(phi) * math.cos(the) * math.cos(psi) + math.sin(phi) * math.sin(the) * math.sin(psi)
22 x1 = math.sin(phi) * math.cos(the) * math.cos(psi) - math.cos(phi) * math.sin(the) * math.sin(psi)
23 y1 = math.cos(phi) * math.sin(the) * math.cos(psi) + math.sin(phi) * math.cos(the) * math.sin(psi)
24 z1 = math.cos(phi) * math.cos(the) * math.sin(psi) - math.sin(phi) * math.sin(the) * math.cos(psi)
30 w2 = math.cos(phi) * math.cos(the) * math.cos(psi) + math.sin(phi) * math.sin(the) * math.sin(psi)
31 x2 = -(math.sin(phi) * math.cos(the) * math.cos(psi) - math.cos(phi) * math.sin(the) * math.sin(psi))
32 y2 = -(math.cos(phi) * math.sin(the) * math.cos(psi) + math.sin(phi) * math.cos(the) * math.sin(psi))
33 z2 = -(math.cos(phi) * math.cos(the) * math.sin(psi) - math.sin(phi) * math.sin(the) * math.cos(psi))
36 w = w1 * w2 - x1 * x2 - y1 * y2 - z1 * z2
37 x = w1 * x2 + x1 * w2 + y1 * z2 - z1 * y2
38 y = w1 * y2 - x1 * z2 + y1 * w2 + z1 * x2
39 z = w1 * z2 + x1 * y2 - y1 * x2 + z1 * w2
48 self.
x = math.atan2(2.0 * (y*z + w*x), squ - sqx - sqy + sqz)
51 sarg = -2.0 * (x*z - w * y)
58 self.
y = math.asin(sarg)
61 self.
z = math.atan2(2.0 * (x*y + w*z), squ + sqx - sqy - sqz)
71 s = math.sqrt(self.
u * self.
u + self.
x * self.
x + self.
y * self.
y + self.
z * self.
z)
85 vec.x = math.atan2(2 * (self.
y*self.
z + self.
u*self.
x), squ - sqx - sqy + sqz);
87 vec.y = math.asin(-2 * (self.
x*self.
z - self.
u*self.
y));
89 vec.z = math.atan2(2 * (self.
x*self.
y + self.
u*self.
z), squ + sqx - sqy - sqz);
94 super(BaseTest, self).
__init__(*args)
122 return math.fmod(math.fmod(angle, 2*math.pi) + 2*math.pi, 2*math.pi)
132 if angle_diff > math.pi:
133 angle_diff = -(2*math.pi - angle_diff)
137 orientation = odom.pose.pose.orientation
138 q =
Q(orientation.x, orientation.y, orientation.z, orientation.w)
140 print "odom received" 141 print "odom pos " +
"x: " + str(odom.pose.pose.position.x)
142 print "odom pos " +
"y: " + str(odom.pose.pose.position.y)
143 print "odom pos " +
"t: " + str(q.getEuler().z)
144 print "odom vel " +
"x: " + str(odom.twist.twist.linear.x)
145 print "odom vel " +
"y: " + str(odom.twist.twist.linear.y)
146 print "odom vel " +
"t: " + str(odom.twist.twist.angular.z)
149 print "base pose ground truth received" 150 print "P3D pose translan: " +
"x: " + str(p3d.pose.pose.position.x)
151 print " " +
"y: " + str(p3d.pose.pose.position.y)
152 print " " +
"z: " + str(p3d.pose.pose.position.z)
153 print "P3D pose rotation: " +
"x: " + str(p3d.pose.pose.orientation.x)
154 print " " +
"y: " + str(p3d.pose.pose.orientation.y)
155 print " " +
"z: " + str(p3d.pose.pose.orientation.z)
156 print " " +
"w: " + str(p3d.pose.pose.orientation.w)
157 print "P3D rate translan: " +
"x: " + str(p3d.twist.twist.linear.x)
158 print " " +
"y: " + str(p3d.twist.twist.linear.y)
159 print " " +
"z: " + str(p3d.twist.twist.linear.z)
160 print "P3D rate rotation: " +
"x: " + str(p3d.twist.twist.angular.x)
161 print " " +
"y: " + str(p3d.twist.twist.angular.y)
162 print " " +
"z: " + str(p3d.twist.twist.angular.z)
166 orientation = odom.pose.pose.orientation
167 q =
Q(orientation.x, orientation.y, orientation.z, orientation.w)
171 self.
odom_xi = odom.pose.pose.position.x
172 self.
odom_yi = odom.pose.pose.position.y
178 self.odom_e.shortest_euler_distance(self.
odom_ei, q.getEuler())
181 q =
Q(p3d.pose.pose.orientation.x , p3d.pose.pose.orientation.y , p3d.pose.pose.orientation.z , p3d.pose.pose.orientation.w)
187 self.
p3d_xi = p3d.pose.pose.position.x
188 self.
p3d_yi = p3d.pose.pose.position.y
192 self.
p3d_x = p3d.pose.pose.position.x - self.
p3d_xi 193 self.
p3d_y = p3d.pose.pose.position.y - self.
p3d_yi 195 self.p3d_e.shortest_euler_distance(self.
p3d_ei,
E(v.x,v.y,v.z))
199 print " odom " +
" x: " + str(self.odom_e.x) +
" y: " + str(self.odom_e.y) +
" t: " + str(self.odom_e.t)
201 print " p3d " +
" x: " + str(self.p3d_e.x) +
" y: " + str(self.p3d_e.y) +
" t: " + str(self.p3d_e.t)
205 print " odom " +
" x: " + str(self.
odom_x) +
" y: " + str(self.
odom_y) +
" t: " + str(self.
odom_t)
207 print " p3d " +
" x: " + str(self.
p3d_x) +
" y: " + str(self.
p3d_y) +
" t: " + str(self.
p3d_t)
211 self.
pub = rospy.Publisher(
"/base_controller/command", Twist)
212 rospy.Subscriber(
"/base_pose_ground_truth", Odometry, self.
p3dInput)
213 rospy.Subscriber(
"/base_odometry/odom", Odometry, self.
odomInput)
214 rospy.init_node(name, anonymous=
True)
def printBaseOdom(self, odom)
def printBaseP3D(self, p3d)
def normalize_angle_positive(self, angle)
def shortest_euler_distance(self, e_from, e_to)
def __init__(self, x, y, z, u)
def shortest_angular_distance(self, angle_from, angle_to)
def __init__(self, x, y, z)
def odomInput(self, odom)
def normalize_angle(self, angle)