Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
extract_rpy_from_quat.Converter Class Reference
Collaboration diagram for extract_rpy_from_quat.Converter:
Collaboration graph

Public Member Functions

def __init__ (self, pub, element_attr, list_attr='')
 
def getElementFromAttributeArray (self, attr_array, data)
 
def normalize (self, array)
 
def convertQuatToVector3 (self, quat)
 
def handle_list (self, msg)
 
def handle_individual (self, msg)
 

Public Attributes

 element_attr_array
 
 list_attr_array
 
 pub
 

Detailed Description

Definition at line 45 of file extract_rpy_from_quat.py.

Constructor & Destructor Documentation

◆ __init__()

def extract_rpy_from_quat.Converter.__init__ (   self,
  pub,
  element_attr,
  list_attr = '' 
)

Definition at line 46 of file extract_rpy_from_quat.py.

46 def __init__(self, pub, element_attr, list_attr=''):
47 self.element_attr_array = element_attr.split('.')
48 self.list_attr_array = list_attr.split('.')
49 self.pub = pub
50

Member Function Documentation

◆ convertQuatToVector3()

def extract_rpy_from_quat.Converter.convertQuatToVector3 (   self,
  quat 
)

Definition at line 71 of file extract_rpy_from_quat.py.

71 def convertQuatToVector3(self, quat):
72 orientation_list = [quat.x, quat.y, quat.z, quat.w]
73 orientation_list = self.normalize(orientation_list)
74 (roll, pitch, yaw) = euler_from_quaternion (orientation_list, axes='sxyz')
75 vector_msg = Vector3()
76 vector_msg.x = roll
77 vector_msg.y = pitch
78 vector_msg.z = yaw
79 return vector_msg
80

References extract_rpy_from_quat.Converter.normalize().

Referenced by extract_rpy_from_quat.Converter.handle_individual(), and extract_rpy_from_quat.Converter.handle_list().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getElementFromAttributeArray()

def extract_rpy_from_quat.Converter.getElementFromAttributeArray (   self,
  attr_array,
  data 
)

Definition at line 51 of file extract_rpy_from_quat.py.

51 def getElementFromAttributeArray(self, attr_array, data):
52 attr_list = []
53 for attr in attr_array:
54 if len(attr_list) == 0:
55 attr_list.append(getattr(data, attr))
56 else:
57 attr_list.append(getattr(attr_list[-1], attr))
58
59 return attr_list[-1]
60

Referenced by extract_rpy_from_quat.Converter.handle_individual(), and extract_rpy_from_quat.Converter.handle_list().

Here is the caller graph for this function:

◆ handle_individual()

def extract_rpy_from_quat.Converter.handle_individual (   self,
  msg 
)

Definition at line 94 of file extract_rpy_from_quat.py.

94 def handle_individual(self, msg):
95 quat = self.getElementFromAttributeArray(self.element_attr_array, msg)
96
97 pose_array_msg = PoseArray()
98
99 fake_pose = Pose()
100 fake_pose.position = self.convertQuatToVector3(quat)
101 fake_pose.orientation = quat
102 pose_array_msg.poses.append(fake_pose)
103
104 self.pub.publish(pose_array_msg)
105
106
107

References extract_rpy_from_quat.Converter.convertQuatToVector3(), extract_rpy_from_quat.Converter.element_attr_array, extract_rpy_from_quat.Converter.getElementFromAttributeArray(), and extract_rpy_from_quat.Converter.pub.

Here is the call graph for this function:

◆ handle_list()

def extract_rpy_from_quat.Converter.handle_list (   self,
  msg 
)

Definition at line 81 of file extract_rpy_from_quat.py.

81 def handle_list(self, msg):
82 list_ele = self.getElementFromAttributeArray(self.list_attr_array, msg)
83
84 pose_array_msg = PoseArray()
85 for e in list_ele:
86 quat = self.getElementFromAttributeArray(self.element_attr_array, e)
87 fake_pose = Pose()
88 fake_pose.position = self.convertQuatToVector3(quat)
89 fake_pose.orientation = quat
90 pose_array_msg.poses.append(fake_pose)
91
92 self.pub.publish(pose_array_msg)
93

References extract_rpy_from_quat.Converter.convertQuatToVector3(), extract_rpy_from_quat.Converter.element_attr_array, extract_rpy_from_quat.Converter.getElementFromAttributeArray(), extract_rpy_from_quat.Converter.list_attr_array, and extract_rpy_from_quat.Converter.pub.

Here is the call graph for this function:

◆ normalize()

def extract_rpy_from_quat.Converter.normalize (   self,
  array 
)
Normalize a 4 element array/list/numpy.array for use as a quaternion
:param quat_array: 4 element list/array
:returns: normalized array
:rtype: numpy array

Definition at line 61 of file extract_rpy_from_quat.py.

61 def normalize(self, array):
62 """
63 Normalize a 4 element array/list/numpy.array for use as a quaternion
64 :param quat_array: 4 element list/array
65 :returns: normalized array
66 :rtype: numpy array
67 """
68 quat = np.array(array)
69 return quat / np.sqrt(np.dot(quat, quat))
70

Referenced by extract_rpy_from_quat.Converter.convertQuatToVector3().

Here is the caller graph for this function:

Member Data Documentation

◆ element_attr_array

extract_rpy_from_quat.Converter.element_attr_array

◆ list_attr_array

extract_rpy_from_quat.Converter.list_attr_array

◆ pub

extract_rpy_from_quat.Converter.pub

The documentation for this class was generated from the following file: