diff --git a/body/stretch_body/dynamixel_hello_XL430.py b/body/stretch_body/dynamixel_hello_XL430.py
index 7e7f98f7..e06142cc 100644
--- a/body/stretch_body/dynamixel_hello_XL430.py
+++ b/body/stretch_body/dynamixel_hello_XL430.py
@@ -106,6 +106,8 @@ def __init__(self, name, chain=None, usb=None):
self.total_range = abs(self.ticks_to_world_rad(self.params['range_t'][0]) - self.ticks_to_world_rad(self.params['range_t'][1]))
self.in_collision_stop = {'pos': False, 'neg': False}
self.ts_collision_stop = {'pos': 0.0, 'neg': 0.0}
+ self.forced_collision_stop_override = {'pos': False, 'neg':False}
+ self._in_collision_stop_override = False
except KeyError:
self.motor=None
@@ -449,22 +451,33 @@ def step_collision_avoidance(self,in_collision):
# print('Invalid IN_COLLISION for joint %s'%self.name)
# return
+ if True in self.forced_collision_stop_override.values():
+ if not self._in_collision_stop_override:
+ self.quick_stop()
+ self._in_collision_stop_override = True
+ return
+
+ if not True in self.forced_collision_stop_override.values():
+ self._in_collision_stop_override = False
+
+
for dir in ['pos','neg']:
if in_collision[dir] and not self.in_collision_stop[dir]:
# Stop current motion
self.ts_collision_stop[dir] = time.time()
- self.quick_stop()
+ if not self.was_runstopped:
+ self.quick_stop()
self.in_collision_stop[dir] = True
- self.last_collision_pair_min_dist = in_collision['las_cp_min_dist']
+ # self.last_collision_pair_min_dist = in_collision['las_cp_min_dist']
+ # self.last_cfg_thresh = in_collision['last_joint_cfg_thresh']
#Reset if out of collision (at least 1s after collision)
- if self.in_collision_stop[dir] and not in_collision[dir] and time.time()-self.ts_collision_stop[dir]>1.0:
- # Check if the minimum distance between the last active collision pair has changed before reset
- if in_collision['las_cp_min_dist']:
- print(f"[{self.name}] Joint in collision {in_collision['las_cp_min_dist']}")
- if self.last_collision_pair_min_dist['pair_name']==in_collision['las_cp_min_dist']['pair_name']:
- if abs(self.last_collision_pair_min_dist['dist'] - in_collision['las_cp_min_dist']['dist'])>0.03:
- self.in_collision_stop[dir] = False
+ if self.in_collision_stop[dir] and not in_collision[dir] and time.time()-self.ts_collision_stop[dir]>1:
+ self.in_collision_stop[dir] = False
+ # if abs(self.last_cfg_thresh - in_collision['last_joint_cfg_thresh']) > 0.001:
+ # self.in_collision_stop[dir] = False
+ # if abs(self.status['vel'])<0.001:
+ # self.in_collision_stop[dir] = False
def get_braking_distance(self,acc=None):
"""Compute distance to brake the joint from the current velocity"""
@@ -591,6 +604,14 @@ def set_velocity(self,v_des,a_des=None):
self.enable_torque()
v = min(self.params['motion']['max']['vel'],abs(v_des))
+ if self.forced_collision_stop_override['pos'] and v_des>0:
+ self.logger.warning(f"Forced Collision stop")
+ return
+
+ if self.forced_collision_stop_override['neg'] and v_des<0:
+ self.logger.warning(f"Forced Collision stop")
+ return
+
if self.in_collision_stop['pos'] and v_des>0:
self.logger.warning('set_velocity in collision . Motion disabled in direction %s for %s. Not executing set_velocity'%('pos',self.name))
return
diff --git a/body/stretch_body/end_of_arm.py b/body/stretch_body/end_of_arm.py
index 10c240e9..99e2fd4f 100644
--- a/body/stretch_body/end_of_arm.py
+++ b/body/stretch_body/end_of_arm.py
@@ -128,7 +128,9 @@ def get_joint_configuration(self,braked=False):
dx=0
ret[j] = motor.status['pos'] + dx
return ret
-
+
+ def pre_stow(self,robot=None):
+ pass
diff --git a/body/stretch_body/end_of_arm_tools.py b/body/stretch_body/end_of_arm_tools.py
index a923a751..7f726d1b 100644
--- a/body/stretch_body/end_of_arm_tools.py
+++ b/body/stretch_body/end_of_arm_tools.py
@@ -75,7 +75,7 @@ def home(self):
self.motors['wrist_roll'].move_to(0)
self.motors['wrist_yaw'].home()
- def pre_stow(self):
+ def pre_stow(self,robot=None):
if 'wrist_pitch' in self.end_of_arm.joints:
self.end_of_arm.move_to('wrist_pitch', self.end_of_arm.params['stow']['wrist_pitch'])
@@ -105,8 +105,10 @@ def home(self):
self.motors['wrist_roll'].move_to(self.params['stow']['wrist_roll'])
self.motors['wrist_yaw'].home()
- def pre_stow(self):
- if 'wrist_pitch' in self.end_of_arm.joints:
+ def pre_stow(self,robot=None):
+ if robot:
+ robot.end_of_arm.move_to('wrist_pitch', robot.end_of_arm.params['stow']['wrist_pitch'])
+ else:
self.end_of_arm.move_to('wrist_pitch', self.end_of_arm.params['stow']['wrist_pitch'])
class EOA_Wrist_DW3_Tool_SG3(EndOfArm):
@@ -138,8 +140,10 @@ def home(self):
self.motors['wrist_yaw'].home()
self.motors['stretch_gripper'].home()
- def pre_stow(self):
- if 'wrist_pitch' in self.end_of_arm.joints:
+ def pre_stow(self,robot=None):
+ if robot:
+ robot.end_of_arm.move_to('wrist_pitch', robot.end_of_arm.params['stow']['wrist_pitch'])
+ else:
self.end_of_arm.move_to('wrist_pitch', self.end_of_arm.params['stow']['wrist_pitch'])
class EOA_Wrist_DW3_Tool_Tablet_12in(EndOfArm):
@@ -156,7 +160,7 @@ def __init__(self, name='eoa_wrist_dw3_tool_tablet_12in'):
'joint_wrist_pitch': 'wrist_pitch',
'joint_wrist_roll':'wrist_roll' #Not mapping fingers for collision mgmt yet
}
-
+
def move_by(self, joint, x_r, v_r=None, a_r=None, enable_wrist_roll = False):
# Lock wrist roll by default
if joint=='wrist_roll':
@@ -228,4 +232,20 @@ def home(self):
self.motors['wrist_yaw'].home()
self.motors['wrist_pitch'].move_to(self.params['stow']['wrist_pitch'])
self.motors['wrist_yaw'].move_to(1.57)
- time.sleep(1)
\ No newline at end of file
+ time.sleep(2)
+
+ def step_sentry(self, robot):
+ super().step_sentry(robot)
+ if robot.collision.running:
+ wrist_p = self.get_joint('wrist_pitch').status['pos']
+ wrist_y = self.get_joint('wrist_yaw').status['pos']
+ # TODO: Add more special conditions around this part
+ if wrist_p > -0.3 and wrist_y < 0.18:
+ # print("In Special Stop")
+ self.get_joint('wrist_yaw').forced_collision_stop_override = {'pos': False, 'neg':True}
+ self.get_joint('wrist_pitch').forced_collision_stop_override = {'pos': True, 'neg':False}
+
+ else:
+ # print("Out Special Stop")
+ self.get_joint('wrist_yaw').forced_collision_stop_override = {'pos': False, 'neg':False}
+ self.get_joint('wrist_pitch').forced_collision_stop_override = {'pos': False, 'neg':False}
\ No newline at end of file
diff --git a/body/stretch_body/gamepad_controller.py b/body/stretch_body/gamepad_controller.py
index 3f6306cb..9ca6b38f 100755
--- a/body/stretch_body/gamepad_controller.py
+++ b/body/stretch_body/gamepad_controller.py
@@ -334,7 +334,7 @@ def main():
for k in state.keys():
print(k, ' : ', state[k])
print('------------------------------')
- time.sleep(1.0)
+ time.sleep(0.1)
except (KeyboardInterrupt, SystemExit):
pass
diff --git a/body/stretch_body/gamepad_teleop.py b/body/stretch_body/gamepad_teleop.py
index d9b109f2..c915d675 100644
--- a/body/stretch_body/gamepad_teleop.py
+++ b/body/stretch_body/gamepad_teleop.py
@@ -53,7 +53,7 @@ def __init__(self, robot_instance = True, print_dongle_status = True, lock=None,
self.end_of_arm_tool =RobotParams().get_params()[1]['robot']['tool']
- self.sleep = 1/50
+ self.sleep = 1/15
self.print_mode = False
self._i = 0
diff --git a/body/stretch_body/prismatic_joint.py b/body/stretch_body/prismatic_joint.py
index f28a36a4..da704e4b 100644
--- a/body/stretch_body/prismatic_joint.py
+++ b/body/stretch_body/prismatic_joint.py
@@ -44,6 +44,7 @@ def __init__(self,name,usb=None):
self.total_range = abs(self.params['range_m'][1] - self.params['range_m'][0])
self.in_collision_stop = {'pos': False, 'neg': False}
self.ts_collision_stop = {'pos': 0, 'neg': 0}
+ self.collision_till_zero_vel_counter = 0
# ########### Device Methods #############
def startup(self, threaded=True):
@@ -591,7 +592,6 @@ def step_collision_avoidance(self,in_collision):
# if in_collision['pos'] and in_collision['neg']:
# print('Invalid IN_COLLISION for joint %s'%self.name)
# return
-
for dir in ['pos','neg']:
if in_collision[dir] and not self.in_collision_stop[dir]:
# Stop current motion
@@ -599,16 +599,20 @@ def step_collision_avoidance(self,in_collision):
self.push_command()
self.in_collision_stop[dir] = True
self.ts_collision_stop[dir]=time.time()
- self.last_collision_pair_min_dist = in_collision['las_cp_min_dist']
+ self.collision_till_zero_vel_counter = 0
+ # self.last_cfg_thresh = in_collision['last_joint_cfg_thresh']
#Reset if out of collision (at least 1s after collision)
if self.in_collision_stop[dir] and not in_collision[dir] and time.time()-self.ts_collision_stop[dir]>1.0:
- # Check if the minimum distance between the last active collision pair has changed before reset
- if in_collision['las_cp_min_dist']:
- print(f"[{self.name}] Joint in collision {in_collision['las_cp_min_dist']}")
- if self.last_collision_pair_min_dist['pair_name']==in_collision['las_cp_min_dist']['pair_name']:
- if abs(self.last_collision_pair_min_dist['dist'] - in_collision['las_cp_min_dist']['dist'])>0.03:
- self.in_collision_stop[dir] = False
+ self.in_collision_stop[dir] = False
+ # if abs(self.last_cfg_thresh - in_collision['last_joint_cfg_thresh']) > 0.001 and abs(self.status['vel'])<0.001:
+ # self.in_collision_stop[dir] = False
+ # if abs(self.status['vel'])<0.001:
+ # self.collision_till_zero_vel_counter = self.collision_till_zero_vel_counter + 1
+ # if self.collision_till_zero_vel_counter>50:
+ # self.in_collision_stop[dir] = False
+ # self.collision_till_zero_vel_counter = 0
+
diff --git a/body/stretch_body/robot.py b/body/stretch_body/robot.py
index 979dfcbe..b9ef8fdf 100644
--- a/body/stretch_body/robot.py
+++ b/body/stretch_body/robot.py
@@ -156,8 +156,8 @@ def step(self):
if self.robot.params['use_sentry']:
if (self.titr % self.sentry_downrate_int) == 0:
self.robot._step_sentry()
- if self.robot.is_homed():
- self.robot.collision.step()
+ # if self.robot.is_homed():
+ # self.robot.collision.step()
if (self.titr % self.trajectory_downrate_int) == 0:
self.robot._update_trajectory_non_dynamixel()
self.stats.mark_loop_end()
@@ -170,6 +170,36 @@ def run(self):
self.step()
self.robot.logger.debug('Shutting down SystemMonitorThread')
+class CollisionMonitorThread(threading.Thread):
+ """
+ This thread runs at 25Hz.
+ It updates the status data of the Devices.
+ It also steps the Sentry, Monitor, and Collision functions
+ """
+ def __init__(self, robot, target_rate_hz=25.0):
+ threading.Thread.__init__(self, name = self.__class__.__name__)
+ self.robot=robot
+ self.robot_update_rate_hz = target_rate_hz
+ self.shutdown_flag = threading.Event()
+ self.stats = hello_utils.LoopStats(loop_name='CollisionMonitorThread',target_loop_rate=self.robot_update_rate_hz)
+ self.titr=0
+ self.running=False
+
+ def step(self):
+ self.titr = self.titr + 1
+ self.stats.mark_loop_start()
+ if self.robot.is_homed():
+ self.robot.collision.step()
+ self.stats.mark_loop_end()
+
+ def run(self):
+ self.running=True
+ while not self.shutdown_flag.is_set():
+ self.stats.wait_until_ready_to_run()
+ if not self.shutdown_flag.is_set():
+ self.step()
+ self.robot.logger.debug('Shutting down CollisionMonitorThread')
+
class Robot(Device):
"""
API to the Stretch Robot
@@ -228,6 +258,7 @@ def __init__(self):
self.sys_thread = None
self.dxl_head_thread = None
self.event_loop_thread = None
+ self.collision_mgmt_thread = None
self.eoa_name= self.params['tool']
module_name = self.robot_params[self.eoa_name]['py_module_name']
@@ -309,6 +340,7 @@ def startup(self,start_non_dxl_thread=True,start_dxl_thread=True,start_sys_mon_t
self.dxl_end_of_arm_thread = DXLEndOfArmStatusThread(self,target_rate_hz=self.params['rates']['DXLStatusThread_Hz'])
self.sys_thread = SystemMonitorThread(self, target_rate_hz=self.params['rates']['SystemMonitorThread_Hz'])
self.dxl_head_thread = DXLHeadStatusThread(self, target_rate_hz=self.params['rates']['DXLStatusThread_Hz'])
+ self.collision_mgmt_thread = CollisionMonitorThread(self, target_rate_hz=100)
if start_non_dxl_thread:
self.non_dxl_thread.setDaemon(True)
@@ -327,6 +359,10 @@ def startup(self,start_non_dxl_thread=True,start_dxl_thread=True,start_sys_mon_t
self.sys_thread.setDaemon(True)
self.sys_thread.start()
+ if start_sys_mon_thread and self.collision_mgmt_thread:
+ self.collision_mgmt_thread.setDaemon(True)
+ self.collision_mgmt_thread.start()
+
return success
def stop(self):
@@ -352,6 +388,10 @@ def stop(self):
if self.sys_thread.running:
self.sys_thread.shutdown_flag.set()
self.sys_thread.join(1)
+ if self.collision_mgmt_thread:
+ if self.collision_mgmt_thread.running:
+ self.collision_mgmt_thread.shutdown_flag.set()
+ self.collision_mgmt_thread.join(1)
for k in self.devices:
if self.devices[k] is not None:
self.logger.debug('Shutting down %s'%k)
diff --git a/body/stretch_body/robot_collision.py b/body/stretch_body/robot_collision.py
index 32e444b0..0f545a47 100644
--- a/body/stretch_body/robot_collision.py
+++ b/body/stretch_body/robot_collision.py
@@ -7,7 +7,11 @@
import time
import threading
import chime
-import math
+import random
+from stretch_body.robot_params import RobotParams
+import multiprocessing
+import signal
+import ctypes
try:
# works on ubunut 22.04
@@ -83,6 +87,85 @@ def check_pts_in_AABB_cube(cube, pts):
return True
return False
+def check_AABB_in_AABB_from_pts(pts1, pts2):
+ """
+ Check if an AABB intersects another AABB from the given two sets of points
+ """
+ print(pts1.shape,pts2.shape)
+ xmax_1 = max(pts1[:, 0])
+ xmin_1 = min(pts1[:, 0])
+ ymax_1 = max(pts1[:, 1])
+ ymin_1 = min(pts1[:, 1])
+ zmax_1 = max(pts1[:, 2])
+ zmin_1 = min(pts1[:, 2])
+
+ xmax_2 = max(pts2[:, 0])
+ xmin_2 = min(pts2[:, 0])
+ ymax_2 = max(pts2[:, 1])
+ ymin_2 = min(pts2[:, 1])
+ zmax_2 = max(pts2[:, 2])
+ zmin_2 = min(pts2[:, 2])
+
+ cx = xmin_1<=xmax_2 and xmax_1>=xmin_2
+ cy = ymin_1<=ymax_2 and ymax_1>=ymin_2
+ cz = zmin_1<=zmax_2 and zmax_1>=zmin_2
+
+ return cx and cy and cz
+
+
+def check_mesh_triangle_edges_in_cube(mesh_triangles,cube):
+ # Check a set of mesh's triangles intersect an AABB cube
+ while len(mesh_triangles):
+ # choose a random triangle indices
+ random_index = random.randint(0, len(mesh_triangles) - 1)
+ points = mesh_triangles[random_index]
+ mesh_triangles.pop(random_index)
+ # Barycentric Coordinates based points based edge points interpolation
+ if check_pts_in_AABB_cube(cube,sample_points_on_triangle_edges(np.array(points))):
+ return True
+ return False
+
+def get_triangle_edge_barycentric_coords(N):
+ """
+ Generate a Barycentric coordinate vectors of N points of a triangle edges
+ This matrix is to be used as a constant.
+ """
+ barycentric_coords = []
+ nums = np.linspace(0,1,num=N)
+ for n1 in nums:
+ for n2 in nums:
+ for n3 in nums:
+ c = False
+ if abs(n3)<0.001:
+ c = True
+ if abs(n2)<0.001:
+ c = True
+ if abs(n1)<0.001:
+ c = True
+ if c and abs((1-n2-n3)-n1)<0.001:
+ barycentric_coords.append([n1,n2,n3])
+
+ return np.array(barycentric_coords)
+
+BARYCENTRIC_COORDS = get_triangle_edge_barycentric_coords(25) # Sample a NX3 Barycentric Coord vector matrix
+
+def sample_points_on_triangle_edges(points):
+ # Convert barycentric coordinates to Cartesian coordinates
+ points = BARYCENTRIC_COORDS[:, 0][:, np.newaxis] * points[0] \
+ + BARYCENTRIC_COORDS[:, 1][:, np.newaxis] * points[1] \
+ + BARYCENTRIC_COORDS[:, 2][:, np.newaxis] * points[2]
+ return points
+
+def scale_cuboid_points(vertices,scale_factor):
+ # Calculate the centroid of the cuboid
+ centroid = np.mean(vertices, axis=0)
+
+ # Scale the vertices relative to the centroid
+ scaled_vertices = centroid + scale_factor * (vertices - centroid)
+
+ # Convert the scaled vertices back to a list of tuples and return
+ return scaled_vertices
+
def check_ppd_edges_in_cube(cube,cube_edge,edge_indices):
if len(edge_indices)!=12:
print('Invalid PPD provided to check_ppd_edges_in_cube')
@@ -117,6 +200,7 @@ def closest_pair_3d(points1, points2):
closest_pair = (p1, p2)
return closest_pair, closest_distance
+
# #######################################################################
class CollisionLink:
@@ -188,6 +272,16 @@ def find_edge_indices_PPD(self):
lens.sort()
print('LENS',lens)
return q
+
+ def get_triangles(self):
+ triangles_idx=self.mesh.cells_dict['triangle']
+ triangles = []
+ for t_set in triangles_idx:
+ p1 = self.pose[t_set[0]]
+ p2 = self.pose[t_set[1]]
+ p3 = self.pose[t_set[2]]
+ triangles.append([p1,p2,p3])
+ return triangles
def check_AABB(self,pts):
"""
@@ -215,13 +309,14 @@ def check_AABB(self,pts):
return True
class CollisionPair:
- def __init__(self, name,link_pts,link_cube,detect_as):
+ def __init__(self, name,link_pts,link_cube,detect_as, cube_scale=1.2):
self.in_collision=False
self.was_in_collision=False
self.link_cube=link_cube
self.link_pts=link_pts
self.detect_as=detect_as
self.name=name
+ self.cube_scale = cube_scale
self.is_valid=self.link_cube.is_valid and self.link_pts.is_valid and self.link_cube.is_aabb
if not self.is_valid:
print('Dropping monitor of collision pair %s'%self.name_id)
@@ -238,19 +333,23 @@ def pretty_print(self):
class CollisionJoint:
- def __init__(self, joint_name,motor):
+ def __init__(self, joint_name):
self.name=joint_name
- self.motor=motor
self.active_collisions=[]
self.collision_pairs=[]
self.collision_dirs={}
- self.in_collision={'pos':False,'neg':False, 'las_cp_min_dist':None}
+ self.in_collision={'pos':False,'neg':False}
self.was_in_collision = {'pos': False, 'neg': False}
+ self.last_in_collision_cnt = 0
def add_collision_pair(self,motion_dir, collision_pair):
self.collision_pairs.append(collision_pair)
self.collision_dirs[collision_pair.name]=motion_dir
+ def update_last_joint_cfg_thresh(self,thresh):
+ self.in_collision['last_joint_cfg_thresh'] = thresh
+
+
def update_collision_pair_min_dist(self,pair_name):
for cp in self.collision_pairs:
if cp.name == pair_name:
@@ -268,9 +367,154 @@ def pretty_print(self):
for ac in self.active_collisions:
print('Active Collision: %s' % ac)
+def _collision_compute_worker(name, shared_is_running, shared_joint_cfg, shared_collision_status, exit_event):
+ signal.signal(signal.SIGINT, signal_handler)
+ signal.signal(signal.SIGTERM, signal_handler)
+ collision_compute = RobotCollisionCompute(name)
+ collision_compute.startup()
+ collision_joints_status = {}
+ time.sleep(0.5)
+ while not exit_event.is_set():
+ try:
+ if shared_is_running.value:
+ collision_compute.step(shared_joint_cfg)
+ for joint_name in collision_compute.collision_joints:
+ collision_joints_status[joint_name] = collision_compute.collision_joints[joint_name].in_collision
+ shared_collision_status.put(collision_joints_status)
+ except (BrokenPipeError,ConnectionResetError):
+ pass
+
+def signal_handler(signal_received, frame):
+ exit(0)
class RobotCollisionMgmt(Device):
- def __init__(self,robot):
+ def __init__(self,robot,name='robot_collision_mgmt'):
+ self.name = name
+ self.robot = robot
+ self.shared_joint_cfg = multiprocessing.Queue()
+ self.shared_collision_status = multiprocessing.Queue()
+ self.shared_is_running = multiprocessing.Value(ctypes.c_bool, False)
+ self.exit_event = multiprocessing.Event()
+ self.collision_compute_proccess = multiprocessing.Process(target=_collision_compute_worker,
+ args=(self.name,
+ self.shared_is_running,
+ self.shared_joint_cfg,
+ self.shared_collision_status,
+ self.exit_event,),daemon=True)
+ self.running = False
+ self.robot_params = RobotParams().get_params()[1]
+ self.collision_status = {}
+
+ def startup(self):
+ self.collision_compute_proccess.start()
+
+ def stop(self):
+ self.exit_event.set()
+ self.shared_is_running.set(False)
+ self.collision_compute_proccess.terminate()
+ self.collision_compute_proccess.join()
+
+ def step(self):
+ try:
+ self.shared_is_running.value = self.running
+ if self.running:
+ config = self.get_joint_configuration(braked=False)
+ self.shared_joint_cfg.put(config)
+ self.collision_status.update(self.shared_collision_status.get())
+ for j in self.collision_status.keys():
+ self.get_joint_motor(j).step_collision_avoidance(self.collision_status[j])
+ except (BrokenPipeError,ConnectionResetError):
+ pass
+
+ def get_joint_motor(self,joint_name):
+ if joint_name=='lift':
+ return self.robot.lift
+ if joint_name=='arm':
+ return self.robot.arm
+ if joint_name=='head_pan':
+ return self.robot.head.get_joint('head_pan')
+ if joint_name=='head_tilt':
+ return self.robot.head.get_joint('head_tilt')
+ #Try the tool
+ return self.robot.end_of_arm.get_joint(joint_name)
+
+ def get_normalized_cfg_threshold(self):
+ arm_pos = self.robot.status['arm']['pos']/(0.5)
+ lift_pos = self.robot.status['lift']['pos']/(1.1)
+ head_pan_pos = (self.robot.status['head']['head_pan']['pos_ticks']- self.robot_params['head_pan']['range_t'][0])/(self.robot_params['head_pan']['range_t'][1] - self.robot_params['head_pan']['range_t'][0])
+ head_tilt_pos = (self.robot.status['head']['head_tilt']['pos_ticks']- self.robot_params['head_tilt']['range_t'][0])/(self.robot_params['head_tilt']['range_t'][1] - self.robot_params['head_tilt']['range_t'][0])
+ thresh = arm_pos + lift_pos + head_pan_pos + head_tilt_pos
+ i = 0
+ for j in self.robot.end_of_arm.joints:
+ value = (self.robot.status['end_of_arm'][j]['pos_ticks']- self.robot_params[j]['range_t'][0])/(self.robot_params['head_pan']['range_t'][1] - self.robot_params[j]['range_t'][0])
+ thresh = thresh + value
+ i = i + 1
+ thresh = thresh/(4+i)
+ return float(thresh)
+
+ def get_joint_configuration(self,braked=False):
+ """
+ Construct a dictionary of robot's current pose
+ """
+ s = self.robot.get_status()
+ kbd = self.robot_params['robot_collision_mgmt'][self.robot.params['model_name']]['k_brake_distance']
+ if braked:
+ da=kbd['arm']*self.robot.arm.get_braking_distance()/4.0
+ dl=kbd['lift']*self.robot.lift.get_braking_distance()
+ dhp = kbd['head_pan'] * self.robot.head.get_joint('head_pan').get_braking_distance()
+ dht = kbd['head_tilt'] * self.robot.head.get_joint('head_tilt').get_braking_distance()
+ else:
+ da=0.0
+ dl=0.0
+ dhp=0.0
+ dht=0.0
+
+ configuration = {
+ 'joint_lift': dl+s['lift']['pos'],
+ 'joint_arm_l0': da+s['arm']['pos']/4.0,
+ 'joint_arm_l1': da+s['arm']['pos']/4.0,
+ 'joint_arm_l2': da+s['arm']['pos']/4.0,
+ 'joint_arm_l3': da+s['arm']['pos']/4.0,
+ 'joint_head_pan': dhp+s['head']['head_pan']['pos'],
+ 'joint_head_tilt': dht+s['head']['head_tilt']['pos']
+ }
+
+ configuration.update(self.robot.end_of_arm.get_joint_configuration(True))
+ return configuration
+
+ def update_configuration_with_brakes(self,configuration):
+ """
+ Update a dictionary of robot's current pose with braking distance applied
+ """
+ s = self.robot.get_status()
+ kbd = self.robot_params['robot_collision_mgmt'][self.robot.params['model_name']]['k_brake_distance']
+ da=kbd['arm']*self.robot.arm.get_braking_distance()/4.0
+ dl=kbd['lift']*self.robot.lift.get_braking_distance()
+ dhp = kbd['head_pan'] * self.robot.head.get_joint('head_pan').get_braking_distance()
+ dht = kbd['head_tilt'] * self.robot.head.get_joint('head_tilt').get_braking_distance()
+
+
+ configuration = {
+ 'joint_lift': dl+s['lift']['pos'],
+ 'joint_arm_l0': da+s['arm']['pos']/4.0,
+ 'joint_arm_l1': da+s['arm']['pos']/4.0,
+ 'joint_arm_l2': da+s['arm']['pos']/4.0,
+ 'joint_arm_l3': da+s['arm']['pos']/4.0,
+ 'joint_head_pan': dhp+s['head']['head_pan']['pos'],
+ 'joint_head_tilt': dht+s['head']['head_tilt']['pos']
+ }
+
+ configuration.update(self.robot.end_of_arm.get_joint_configuration(True))
+ return configuration
+
+ def enable(self):
+ self.running=True
+
+ def disable(self):
+ self.running=False
+
+class RobotCollisionCompute(Device):
+ def __init__(self,name='robot_collision_mgmt'):
"""
RobotCollisionMgmt monitors for collisions between links.
It utilizes the Collision mesh for collision estimation.
@@ -283,30 +527,26 @@ def __init__(self,robot):
Each link includes a parameter "scale_pct" which allows the mesh size to be expanded by a percentage around its centroid
enabling the ability to increase the safety zone.
"""
- Device.__init__(self, name='robot_collision_mgmt')
- self.robot = robot
+ Device.__init__(self, name)
self.collision_joints = {}
self.collision_links = {}
self.collision_pairs = {}
- #chime.theme('big-sur') #'material')#
- self.running=False
+ chime.theme('big-sur') #'material')
self.urdf=None
self.prev_loop_start_ts = None
+ self.robot_params = RobotParams().get_params()[1]
def pretty_print(self):
for j in self.collision_joints:
self.collision_joints[j].pretty_print()
- def enable(self):
- self.running=True
- def disable(self):
- self.running=False
+
def startup(self,threaded=False):
- Device.startup(self, threaded=False)
+ Device.startup(self, threaded)
pkg = str(importlib_resources.files("stretch_urdf")) # .local/lib/python3.10/site-packages/stretch_urdf)
- model_name = self.robot.params['model_name']
- eoa_name= self.robot.params['tool']
+ model_name = self.robot_params['robot']['model_name']
+ eoa_name= self.robot_params['robot']['tool']
urdf_name = pkg + '/%s/stretch_description_%s_%s.urdf' % (model_name, model_name, eoa_name)
mesh_path = pkg + '/%s/' % (model_name)
@@ -325,7 +565,7 @@ def startup(self,threaded=False):
#Construct collision pairs
cp_dict = self.params[model_name]['collision_pairs']
- cp_dict.update(self.robot.end_of_arm.params['collision_mgmt']['collision_pairs'])
+ cp_dict.update(self.robot_params[eoa_name]['collision_mgmt']['collision_pairs'])
for cp_name in cp_dict:
cp=cp_dict[cp_name] #Eg {'link_pts': 'link_head_tilt', 'link_cube': 'link_arm_l4','detect_as':'pts'}
@@ -339,12 +579,14 @@ def startup(self,threaded=False):
link_pts=self.collision_links[cp['link_pts']],
link_cube=self.collision_links[cp['link_cube']],
detect_as=cp['detect_as'])
+ if 'cube_scale' in list(cp.keys()):
+ self.collision_pairs[cp_name].cube_scale = cp['cube_scale']
#Assign collision pairs to each joint
#Include those of standard robot body plus its defined tool
# EG collision_joints={'lift':[{collision_1},{collision_2...}],'head_pan':[...]}
cj_dict=self.params[model_name]['joints']
- eoa_cj_dict=self.robot.end_of_arm.params['collision_mgmt']['joints']
+ eoa_cj_dict=self.robot_params[eoa_name]['collision_mgmt']['joints']
for tt in eoa_cj_dict:
if tt in cj_dict:
@@ -353,43 +595,32 @@ def startup(self,threaded=False):
cj_dict[tt]=eoa_cj_dict[tt]
for joint_name in cj_dict:
- self.collision_joints[joint_name]=CollisionJoint(joint_name,self.get_joint_motor(joint_name))
+ self.collision_joints[joint_name]=CollisionJoint(joint_name)
cp_list = cj_dict[joint_name]
for cp in cp_list: #eg cp={'motion_dir': 'pos', 'collision_pair': 'link_head_tilt_TO_link_arm_l4'}
self.collision_joints[joint_name].add_collision_pair(motion_dir=cp['motion_dir'],
collision_pair=self.collision_pairs[cp['collision_pair']])
-
- def get_joint_motor(self,joint_name):
- if joint_name=='lift':
- return self.robot.lift
- if joint_name=='arm':
- return self.robot.arm
- if joint_name=='head_pan':
- return self.robot.head.get_joint('head_pan')
- if joint_name=='head_tilt':
- return self.robot.head.get_joint('head_tilt')
- #Try the tool
- return self.robot.end_of_arm.get_joint(joint_name)
-
+
def step(self,cfg=None):
"""
Check for interference between cube pairs
"""
- if self.prev_loop_start_ts:
- print(f"[{self.name}] Step exec time: {(time.perf_counter()-self.prev_loop_start_ts)*1000}ms")
+ # if self.prev_loop_start_ts:
+ # print(f"[{self.name}] Step exec time: {(time.perf_counter()-self.prev_loop_start_ts)*1000}ms")
- if self.urdf is None or not self.running:
+ if self.urdf is None:
return
- if cfg is None:
- cfg = self.get_joint_configuration(braked=True)#_braked()
+ # if cfg is None:
+ # cfg = self.get_joint_configuration(braked=True)#_braked()
# Update forward kinematics of links
- lfk = self.urdf.link_fk(cfg=cfg, links=self.collision_links.keys(), use_names=True)
+ _cfg = cfg.get()
+ lfk = self.urdf.link_fk(cfg=_cfg, links=self.collision_links.keys(), use_names=True)
# Update poses of links based on fk
- for link_name in lfk:
+ for link_name in lfk:
self.collision_links[link_name].set_pose(lfk[link_name].dot(
self.collision_links[link_name].points.transpose()).transpose())
@@ -400,20 +631,27 @@ def step(self,cfg=None):
for joint_name in self.collision_joints:
self.collision_joints[joint_name].active_collisions=[]
self.collision_joints[joint_name].was_in_collision = self.collision_joints[joint_name].in_collision.copy()
- # self.collision_joints[joint_name].in_collision = {'pos': False, 'neg': False, 'min_dist_pair':None}
- self.collision_joints[joint_name].in_collision['pos'] = False
- self.collision_joints[joint_name].in_collision['neg'] = False
+ # print(f"[{joint_name}] Was in Collision cnt: {self.collision_joints[joint_name].last_in_collision_cnt}")
+ # Release Collision Joints in_collision mode onlt after 100 cycles
+ if self.collision_joints[joint_name].in_collision['pos'] or self.collision_joints[joint_name].in_collision['neg']:
+ self.collision_joints[joint_name].last_in_collision_cnt = self.collision_joints[joint_name].last_in_collision_cnt + 1
+ if self.collision_joints[joint_name].last_in_collision_cnt > 20:
+ self.collision_joints[joint_name].in_collision['pos'] = False
+ self.collision_joints[joint_name].in_collision['neg'] = False
+ self.collision_joints[joint_name].last_in_collision_cnt = 0
# Test for collisions across all collision pairs
for pair_name in self.collision_pairs:
cp=self.collision_pairs[pair_name]
if cp.is_valid:
cp.was_in_collision=cp.in_collision
if cp.detect_as=='pts':
- cp.in_collision=check_pts_in_AABB_cube(cube=cp.link_cube.pose,pts=cp.link_pts.pose)
- # elif cp.detect_as=='edges':
- # print('Checking', cp.name)
- # cp.in_collision = check_ppd_edges_in_cube(cube=cp.link_cube.pose, cube_edge=cp.link_pts.pose,edge_indices=cp.link_pts.edge_indices_ppd)
+ cp.in_collision=check_pts_in_AABB_cube(cube = scale_cuboid_points(cp.link_cube.pose,cp.cube_scale),
+ pts = cp.link_pts.pose)
+ # cp.in_collision=check_AABB_in_AABB_from_pts(pts1=cp.link_cube.pose,pts2=cp.link_pts.pose)
+ elif cp.detect_as=='edges':
+ cp.in_collision = check_mesh_triangle_edges_in_cube(mesh_triangles = cp.link_pts.get_triangles(),
+ cube = scale_cuboid_points(cp.link_cube.pose,cp.cube_scale))
else:
cp.in_collision =False
#cp.pretty_print()
@@ -424,10 +662,10 @@ def step(self,cfg=None):
# Beep on new collision
if not self.collision_pairs[pair_name].was_in_collision and self.collision_pairs[pair_name].in_collision:
- print('New collision pair event: %s'%pair_name)
- # print('\a')
+ print(f'New collision pair event: {pair_name} [{time.time()}]' )
self.alert()
+ # print(f"From Process: Normal CFG = {normalized_joint_status_thresh}")
#Now update joint state
for joint_name in self.collision_joints:
cj = self.collision_joints[joint_name]
@@ -435,12 +673,8 @@ def step(self,cfg=None):
if cp.in_collision:
cj.active_collisions.append(cp.name) #Add collision to joint
cj.in_collision[cj.collision_dirs[cp.name]] = True
- cj.update_collision_pair_min_dist(cp.name)
-
- if cj.in_collision['las_cp_min_dist']:
- self.collision_joints[joint_name].update_collision_pair_min_dist(cj.in_collision['las_cp_min_dist']['pair_name'])
- #Finally, update the collision state for each joint
- self.collision_joints[joint_name].motor.step_collision_avoidance(self.collision_joints[joint_name].in_collision)
+ # print(f"From Process: {joint_name} = {self.collision_joints[joint_name].in_collision}")
+ # self.collision_joints[joint_name].motor.step_collision_avoidance(self.collision_joints[joint_name].in_collision)
self.prev_loop_start_ts = time.perf_counter()
def alert(self):
@@ -463,37 +697,6 @@ def was_link_in_collsion(self,link_name):
return False
- def get_joint_configuration(self,braked=False):
- """
- Construct a dictionary of robot's current pose
- """
- s = self.robot.get_status()
-
- kbd = self.params[self.robot.params['model_name']]['k_brake_distance']
- if braked:
- da=kbd['arm']*self.robot.arm.get_braking_distance()/4.0
- dl=kbd['lift']*self.robot.lift.get_braking_distance()
- dhp = kbd['head_pan'] * self.robot.head.get_joint('head_pan').get_braking_distance()
- dht = kbd['head_tilt'] * self.robot.head.get_joint('head_tilt').get_braking_distance()
- else:
- da=0.0
- dl=0.0
- dhp=0.0
- dht=0.0
-
- configuration = {
- 'joint_lift': dl+s['lift']['pos'],
- 'joint_arm_l0': da+s['arm']['pos']/4.0,
- 'joint_arm_l1': da+s['arm']['pos']/4.0,
- 'joint_arm_l2': da+s['arm']['pos']/4.0,
- 'joint_arm_l3': da+s['arm']['pos']/4.0,
- 'joint_head_pan': dhp+s['head']['head_pan']['pos'],
- 'joint_head_tilt': dht+s['head']['head_tilt']['pos']
- }
-
- configuration.update(self.robot.end_of_arm.get_joint_configuration(braked))
- return configuration
-
class RobotCollision(Device):
"""
Deprecated. Keep shell class (for now) to avoid breaking legacy code.
diff --git a/body/stretch_body/robot_params_SE3.py b/body/stretch_body/robot_params_SE3.py
index b141d67c..78530627 100644
--- a/body/stretch_body/robot_params_SE3.py
+++ b/body/stretch_body/robot_params_SE3.py
@@ -277,18 +277,24 @@
'stretch_gripper':0.0
},
'collision_mgmt': {
- 'k_brake_distance': {'wrist_pitch': 0.25, 'wrist_yaw': 0.25, 'wrist_roll': 0.25, 'stretch_gripper': 0.0},
+ 'k_brake_distance': {'wrist_pitch': 3.0, 'wrist_yaw': 4.0, 'wrist_roll': 2.0, 'stretch_gripper': 0.0},
'collision_pairs': {
- 'link_gripper_fingertip_left_TO_link_lift': {'link_pts': 'link_gripper_fingertip_left', 'link_cube': 'link_lift','detect_as': 'pts'},
- 'link_gripper_s3_body_TO_base_link': {'link_pts': 'link_gripper_s3_body', 'link_cube': 'base_link','detect_as': 'pts'},
- 'link_wrist_pitch_TO_base_link': {'link_pts': 'link_wrist_pitch', 'link_cube': 'base_link','detect_as': 'pts'},
- 'link_wrist_yaw_bottom_TO_base_link': {'link_pts': 'link_wrist_yaw_bottom', 'link_cube': 'base_link','detect_as': 'pts'},
- 'link_gripper_finger_left_TO_base_link': {'link_pts': 'link_gripper_finger_left','link_cube': 'base_link', 'detect_as': 'pts'},
- 'link_gripper_finger_right_TO_base_link': {'link_pts': 'link_gripper_finger_right','link_cube': 'base_link', 'detect_as': 'pts'},
- 'link_gripper_fingertip_left_TO_base_link': {'link_pts': 'link_gripper_fingertip_left','link_cube': 'base_link', 'detect_as': 'pts'},
- 'link_gripper_fingertip_right_TO_base_link': {'link_pts': 'link_gripper_fingertip_right','link_cube': 'base_link', 'detect_as': 'pts'},
- 'link_gripper_s3_body_TO_link_arm_l0': {'link_pts': 'link_gripper_s3_body', 'link_cube': 'link_arm_l0','detect_as': 'pts'},
- 'link_gripper_s3_body_TO_link_arm_l1': {'link_pts': 'link_gripper_s3_body', 'link_cube': 'link_arm_l1','detect_as': 'pts'}},
+ 'link_gripper_fingertip_left_TO_link_lift': {'link_pts': 'link_gripper_fingertip_left', 'link_cube': 'link_lift','detect_as': 'edges'},
+ 'link_gripper_s3_body_TO_base_link': {'link_pts': 'link_gripper_s3_body', 'link_cube': 'base_link','detect_as': 'edges'},
+ 'link_wrist_pitch_TO_base_link': {'link_pts': 'link_wrist_pitch', 'link_cube': 'base_link','detect_as': 'edges'},
+ 'link_wrist_yaw_bottom_TO_base_link': {'link_pts': 'link_wrist_yaw_bottom', 'link_cube': 'base_link','detect_as': 'edges'},
+ 'link_gripper_finger_left_TO_base_link': {'link_pts': 'link_gripper_finger_left','link_cube': 'base_link', 'detect_as': 'edges'},
+ 'link_gripper_finger_right_TO_base_link': {'link_pts': 'link_gripper_finger_right','link_cube': 'base_link', 'detect_as': 'edges'},
+ 'link_gripper_fingertip_left_TO_base_link': {'link_pts': 'link_gripper_fingertip_left','link_cube': 'base_link', 'detect_as': 'edges'},
+ 'link_gripper_fingertip_right_TO_base_link': {'link_pts': 'link_gripper_fingertip_right','link_cube': 'base_link', 'detect_as': 'edges'},
+ 'link_gripper_s3_body_TO_link_arm_l0': {'link_pts': 'link_gripper_s3_body', 'link_cube': 'link_arm_l0','detect_as': 'edges'},
+ 'link_gripper_s3_body_TO_link_arm_l1': {'link_pts': 'link_gripper_s3_body', 'link_cube': 'link_arm_l1','detect_as': 'edges'},
+ 'link_gripper_s3_body_TO_link_head_tilt': {'link_cube': 'link_head_tilt', 'link_pts': 'link_gripper_s3_body','detect_as': 'edges'},
+ 'link_gripper_finger_left_TO_link_head_tilt': {'link_cube': 'link_head_tilt', 'link_pts': 'link_gripper_finger_left','detect_as': 'edges'},
+ 'link_gripper_finger_right_TO_link_head_tilt': {'link_cube': 'link_head_tilt', 'link_pts': 'link_gripper_finger_right','detect_as': 'edges'},
+ 'link_gripper_finger_right_link_arm_l0': {'link_pts': 'link_gripper_finger_right', 'link_cube': 'link_arm_l0','detect_as': 'edges'},
+ 'link_gripper_finger_left_TO_link_arm_l1': {'link_pts': 'link_gripper_finger_left', 'link_cube': 'link_arm_l1','detect_as': 'edges'},},
+
'joints': {'arm': [{'motion_dir': 'neg', 'collision_pair': 'link_gripper_fingertip_right_TO_base_link'},
{'motion_dir': 'neg', 'collision_pair': 'link_gripper_s3_body_TO_base_link'},
{'motion_dir': 'neg', 'collision_pair': 'link_wrist_pitch_TO_base_link'}],
@@ -298,21 +304,43 @@
{'motion_dir': 'neg', 'collision_pair': 'link_gripper_finger_left_TO_base_link'},
{'motion_dir': 'neg', 'collision_pair': 'link_gripper_finger_right_TO_base_link'},
{'motion_dir': 'neg', 'collision_pair': 'link_gripper_fingertip_left_TO_base_link'},
- {'motion_dir': 'neg', 'collision_pair': 'link_gripper_fingertip_right_TO_base_link'}],
+ {'motion_dir': 'neg', 'collision_pair': 'link_gripper_fingertip_right_TO_base_link'},
+ {'motion_dir': 'pos','collision_pair': 'link_gripper_s3_body_TO_link_head_tilt'},
+ {'motion_dir': 'pos','collision_pair': 'link_gripper_finger_left_TO_link_head_tilt'},
+ {'motion_dir': 'pos','collision_pair': 'link_gripper_finger_right_TO_link_head_tilt'}],
'wrist_pitch': [{'motion_dir': 'neg', 'collision_pair': 'link_gripper_s3_body_TO_base_link'},
{'motion_dir': 'neg', 'collision_pair': 'link_gripper_finger_left_TO_base_link'},
{'motion_dir': 'neg','collision_pair': 'link_gripper_finger_right_TO_base_link'},
{'motion_dir': 'neg','collision_pair': 'link_gripper_fingertip_left_TO_base_link'},
{'motion_dir': 'neg','collision_pair': 'link_gripper_fingertip_right_TO_base_link'},
+ {'motion_dir': 'neg','collision_pair': 'link_gripper_s3_body_TO_link_head_tilt'},
+ {'motion_dir': 'neg','collision_pair': 'link_gripper_finger_left_TO_link_head_tilt'},
+ {'motion_dir': 'neg','collision_pair': 'link_gripper_finger_right_TO_link_head_tilt'},
{'motion_dir': 'pos', 'collision_pair': 'link_gripper_s3_body_TO_link_arm_l0'},
- {'motion_dir': 'pos', 'collision_pair': 'link_gripper_s3_body_TO_link_arm_l1'}],
+ {'motion_dir': 'pos', 'collision_pair': 'link_gripper_s3_body_TO_link_arm_l1'},
+ {'motion_dir': 'pos','collision_pair': 'link_gripper_s3_body_TO_link_head_tilt'},
+ {'motion_dir': 'pos','collision_pair': 'link_gripper_finger_left_TO_link_head_tilt'},
+ {'motion_dir': 'pos','collision_pair': 'link_gripper_finger_right_TO_link_head_tilt'},
+ {'motion_dir': 'pos','collision_pair': 'link_gripper_fingertip_left_TO_link_lift'}],
'wrist_roll': [{'motion_dir': 'neg', 'collision_pair': 'link_gripper_s3_body_TO_link_arm_l1'},
- {'motion_dir': 'pos', 'collision_pair': 'link_gripper_s3_body_TO_link_arm_l0'}],
+ {'motion_dir': 'neg', 'collision_pair': 'link_gripper_s3_body_TO_link_arm_l0'},
+ {'motion_dir': 'pos', 'collision_pair': 'link_gripper_s3_body_TO_link_arm_l0'},
+ # {'motion_dir': 'pos', 'collision_pair': 'link_gripper_s3_body_TO_link_arm_l1'},
+ {'motion_dir': 'pos', 'collision_pair': 'link_gripper_s3_body_TO_base_link'},
+ {'motion_dir': 'neg', 'collision_pair': 'link_gripper_s3_body_TO_base_link'}],
'wrist_yaw': [{'motion_dir': 'pos', 'collision_pair': 'link_gripper_fingertip_left_TO_link_lift'},
{'motion_dir': 'neg', 'collision_pair': 'link_gripper_finger_right_TO_base_link'},
{'motion_dir': 'pos', 'collision_pair': 'link_gripper_finger_left_TO_base_link'},
{'motion_dir': 'neg', 'collision_pair': 'link_gripper_s3_body_TO_link_arm_l0'},
- {'motion_dir': 'pos', 'collision_pair': 'link_gripper_s3_body_TO_link_arm_l1'}]}},
+ {'motion_dir': 'pos', 'collision_pair': 'link_gripper_s3_body_TO_link_arm_l1'},
+ # {'motion_dir': 'pos','collision_pair': 'link_gripper_s3_body_TO_link_head_tilt'},
+ {'motion_dir': 'pos', 'collision_pair': 'link_gripper_s3_body_TO_base_link'},
+ {'motion_dir': 'neg', 'collision_pair': 'link_gripper_s3_body_TO_base_link'},
+ {'motion_dir': 'pos','collision_pair': 'link_gripper_finger_left_TO_link_head_tilt'},
+ {'motion_dir': 'pos','collision_pair': 'link_gripper_finger_right_TO_link_head_tilt'},
+ {'motion_dir': 'neg','collision_pair': 'link_gripper_s3_body_TO_link_head_tilt'},
+ {'motion_dir': 'pos','collision_pair': 'link_gripper_finger_left_TO_link_head_tilt'},
+ {'motion_dir': 'neg','collision_pair': 'link_gripper_finger_right_TO_link_head_tilt'}]}},
'devices': {
'wrist_pitch': {
@@ -399,20 +427,14 @@
'wrist_yaw': 1.57
},
'collision_mgmt': {
- 'k_brake_distance': {'wrist_pitch': 1, 'wrist_yaw':1, 'wrist_roll': 0.25},
+ 'k_brake_distance': {'wrist_pitch': 0.5, 'wrist_yaw':0.5, 'wrist_roll': 0.25},
'collision_pairs': {
- 'link_DW3_tablet_12in_TO_base_link': {'link_cube': 'link_DW3_tablet_12in', 'link_pts': 'base_link', 'detect_as': 'pts'},
- 'link_DW3_tablet_12in_TO_link_arm_l0': {'link_cube': 'link_DW3_tablet_12in', 'link_pts': 'link_arm_l0','detect_as': 'pts'},
- 'link_DW3_tablet_12in_TO_link_arm_l1': {'link_cube': 'link_DW3_tablet_12in', 'link_pts': 'link_arm_l1','detect_as': 'pts'},
- 'link_DW3_tablet_12in_TO_link_head_tilt': {'link_cube': 'link_DW3_tablet_12in', 'link_pts': 'link_head_tilt','detect_as': 'pts'},
-
- 'link_DW3_tablet_12in_TO_base_link': {'link_pts': 'link_DW3_tablet_12in', 'link_cube': 'base_link', 'detect_as': 'pts'},
- 'link_DW3_tablet_12in_TO_link_arm_l0': {'link_pts': 'link_DW3_tablet_12in', 'link_cube': 'link_arm_l0','detect_as': 'pts'},
- 'link_DW3_tablet_12in_TO_link_arm_l1': {'link_pts': 'link_DW3_tablet_12in', 'link_cube': 'link_arm_l1','detect_as': 'pts'},
- 'link_DW3_tablet_12in_TO_link_head_tilt': {'link_pts': 'link_DW3_tablet_12in', 'link_cube': 'link_head_tilt','detect_as': 'pts'},
-
- 'link_wrist_pitch_TO_base_link': {'link_pts': 'link_wrist_pitch', 'link_cube': 'base_link','detect_as': 'pts'},
- 'link_wrist_yaw_bottom_TO_base_link': {'link_pts': 'link_wrist_yaw_bottom', 'link_cube': 'base_link','detect_as': 'pts'}},
+ 'link_DW3_tablet_12in_TO_base_link': {'link_cube': 'base_link', 'link_pts': 'link_DW3_tablet_12in', 'detect_as': 'edges'},
+ 'link_DW3_tablet_12in_TO_link_arm_l0': {'link_cube': 'link_arm_l0', 'link_pts': 'link_DW3_tablet_12in','detect_as': 'edges'},
+ 'link_DW3_tablet_12in_TO_link_arm_l1': {'link_cube': 'link_arm_l1', 'link_pts': 'link_DW3_tablet_12in','detect_as': 'edges'},
+ 'link_DW3_tablet_12in_TO_link_head_tilt': {'link_cube': 'link_head_tilt', 'link_pts': 'link_DW3_tablet_12in','detect_as': 'edges', 'cube_scale': 1.2},
+ 'link_wrist_pitch_TO_base_link': {'link_pts': 'link_wrist_pitch', 'link_cube': 'base_link','detect_as': 'edges'},
+ 'link_wrist_yaw_bottom_TO_base_link': {'link_pts': 'link_wrist_yaw_bottom', 'link_cube': 'base_link','detect_as': 'edges'}},
'joints': {'arm': [{'motion_dir': 'neg', 'collision_pair': 'link_DW3_tablet_12in_TO_base_link'},
{'motion_dir': 'neg', 'collision_pair': 'link_wrist_pitch_TO_base_link'},
@@ -424,21 +446,26 @@
{'motion_dir': 'pos', 'collision_pair': 'link_DW3_tablet_12in_TO_link_head_tilt'}],
'wrist_pitch': [{'motion_dir': 'neg', 'collision_pair': 'link_DW3_tablet_12in_TO_base_link'},
- {'motion_dir': 'pos', 'collision_pair': 'link_DW3_tablet_12in_TO_link_arm_l0'},
+ # {'motion_dir': 'pos', 'collision_pair': 'link_DW3_tablet_12in_TO_base_link'},
+ # {'motion_dir': 'pos', 'collision_pair': 'link_DW3_tablet_12in_TO_link_arm_l0'},
{'motion_dir': 'pos', 'collision_pair': 'link_DW3_tablet_12in_TO_link_arm_l1'},
- {'motion_dir': 'pos', 'collision_pair': 'link_DW3_tablet_12in_TO_link_head_tilt'}],
+ # {'motion_dir': 'neg', 'collision_pair': 'link_DW3_tablet_12in_TO_link_head_tilt'},
+ {'motion_dir': 'pos', 'collision_pair': 'link_DW3_tablet_12in_TO_link_head_tilt'}
+ ],
'wrist_roll': [{'motion_dir': 'neg', 'collision_pair': 'link_DW3_tablet_12in_TO_link_arm_l1'},
{'motion_dir': 'pos', 'collision_pair': 'link_DW3_tablet_12in_TO_link_arm_l0'}],
- 'wrist_yaw': [{'motion_dir': 'neg', 'collision_pair': 'link_DW3_tablet_12in_TO_link_arm_l0'},
- {'motion_dir': 'pos', 'collision_pair': 'link_DW3_tablet_12in_TO_link_arm_l0'},
+ 'wrist_yaw': [
+ {'motion_dir': 'neg', 'collision_pair': 'link_DW3_tablet_12in_TO_link_arm_l0'},
{'motion_dir': 'neg', 'collision_pair': 'link_DW3_tablet_12in_TO_link_arm_l1'},
+ # {'motion_dir': 'neg', 'collision_pair': 'link_DW3_tablet_12in_TO_link_arm_l0'},
{'motion_dir': 'pos', 'collision_pair': 'link_DW3_tablet_12in_TO_link_arm_l1'},
{'motion_dir': 'neg', 'collision_pair': 'link_DW3_tablet_12in_TO_base_link'},
- {'motion_dir': 'pos', 'collision_pair': 'link_DW3_tablet_12in_TO_base_link'}],
-
- 'wrist_yaw': [{'motion_dir': 'pos', 'collision_pair': 'link_DW3_tablet_12in_TO_link_head_tilt'}],
+ {'motion_dir': 'pos', 'collision_pair': 'link_DW3_tablet_12in_TO_base_link'},
+ {'motion_dir': 'pos', 'collision_pair': 'link_DW3_tablet_12in_TO_link_head_tilt'},
+ # {'motion_dir': 'neg', 'collision_pair': 'link_DW3_tablet_12in_TO_link_head_tilt'},
+ ],
'wrist_roll': [{'motion_dir': 'neg', 'collision_pair': 'link_DW3_tablet_12in_TO_link_arm_l0'},
{'motion_dir': 'pos', 'collision_pair': 'link_DW3_tablet_12in_TO_link_arm_l1'}]
@@ -899,7 +926,7 @@
'robot_collision_mgmt': {
'max_mesh_points': 48,
'SE3': {
- 'k_brake_distance': {'lift': 0.75, 'arm': 0.125, 'wrist_yaw': 0.125, 'head_pan': 0.125, 'head_tilt': 0.125},
+ 'k_brake_distance': {'lift': 1.75, 'arm': 1.125, 'wrist_yaw': 0.125, 'head_pan': 0.125, 'head_tilt': 0.125},
'collision_pairs':{'link_head_tilt_TO_link_arm_l4':{'link_pts': 'link_head_tilt', 'link_cube': 'link_arm_l4','detect_as':'pts'},
'link_arm_l0_TO_base_link':{'link_pts': 'link_arm_l0', 'link_cube': 'base_link','detect_as':'pts'}},
diff --git a/tools/bin/profile.html b/tools/bin/profile.html
new file mode 100644
index 00000000..e21e0bf7
--- /dev/null
+++ b/tools/bin/profile.html
@@ -0,0 +1,61912 @@
+
+
+
+
+
+
+
+ Scalene
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ AI optimization options
+
+ AI service provider:
+
+ OpenAI
+
+ Local
+
+
+
+
+
OpenAI API key :
+
+
+
+
+ Language model:
+
+
+ GPT 3.5
+ GPT 4.0
+
+
+
+
+
+ AWS Access Key ID:
+
+
+ AWS Secret Access Key:
+
+
+
+ Language model:
+
+
+ Claude 2.1
+
+
+
+
+
+ Use this option if you are running a local language model. We currently support
Ollama .
+
+
IP Address:
+
+
Port:
+
+
+
+ Server not found or no language models installed.
+ Install language models as in ollama pull codellama:34b-python
.
+
+
+
+
+
+ Language model:
+
+
+
+
+
+
+
+ Proposed optimizations
+
+
+
+ Optimize runtime performance
+
+
+
+
+
+ Optimize memory efficiency
+
+
+
+
+
+ Include GPU optimizations
+
+
+
+ Click on an explosion (💥) to see proposed optimizations for a region of code,
+ or on a lightning bolt (⚡) to propose optimizations for a specific line.
+ Click again to generate a different one.
+ Note that optimizations are AI-generated and may not be correct.
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/tools/bin/profile.json b/tools/bin/profile.json
new file mode 100644
index 00000000..80bc9418
--- /dev/null
+++ b/tools/bin/profile.json
@@ -0,0 +1,57029 @@
+{
+ "alloc_samples": 11,
+ "args": [
+ "stretch_gamepad_teleop.py"
+ ],
+ "elapsed_time_sec": 2.1928789615631104,
+ "entrypoint_dir": "/home/hello-robot/repos/stretch_body/tools/bin",
+ "filename": "/home/hello-robot/repos/stretch_body/tools/bin",
+ "files": {
+ "/home/hello-robot/repos/stretch_body/body/stretch_body/dynamixel_XL430.py": {
+ "functions": [],
+ "imports": [
+ "from __future__ import print_function",
+ "import struct",
+ "import array as arr",
+ "import threading",
+ "import signal"
+ ],
+ "leaks": {},
+ "lines": [
+ {
+ "end_outermost_loop": 1,
+ "end_region_line": 1,
+ "line": "from __future__ import print_function\n",
+ "lineno": 1,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1,
+ "start_region_line": 1
+ },
+ {
+ "end_outermost_loop": 2,
+ "end_region_line": 2,
+ "line": "import struct\n",
+ "lineno": 2,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 2,
+ "start_region_line": 2
+ },
+ {
+ "end_outermost_loop": 3,
+ "end_region_line": 3,
+ "line": "import array as arr\n",
+ "lineno": 3,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 3,
+ "start_region_line": 3
+ },
+ {
+ "end_outermost_loop": 4,
+ "end_region_line": 4,
+ "line": "import logging\n",
+ "lineno": 4,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 4,
+ "start_region_line": 4
+ },
+ {
+ "end_outermost_loop": 5,
+ "end_region_line": 5,
+ "line": "\n",
+ "lineno": 5,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 5,
+ "start_region_line": 5
+ },
+ {
+ "end_outermost_loop": 6,
+ "end_region_line": 6,
+ "line": "from dynamixel_sdk.robotis_def import *\n",
+ "lineno": 6,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 6,
+ "start_region_line": 6
+ },
+ {
+ "end_outermost_loop": 7,
+ "end_region_line": 7,
+ "line": "import dynamixel_sdk.port_handler as prh\n",
+ "lineno": 7,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 7,
+ "start_region_line": 7
+ },
+ {
+ "end_outermost_loop": 8,
+ "end_region_line": 8,
+ "line": "import dynamixel_sdk.packet_handler as pch\n",
+ "lineno": 8,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 8,
+ "start_region_line": 8
+ },
+ {
+ "end_outermost_loop": 9,
+ "end_region_line": 9,
+ "line": "import threading\n",
+ "lineno": 9,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 9,
+ "start_region_line": 9
+ },
+ {
+ "end_outermost_loop": 10,
+ "end_region_line": 10,
+ "line": "import serial\n",
+ "lineno": 10,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 10,
+ "start_region_line": 10
+ },
+ {
+ "end_outermost_loop": 11,
+ "end_region_line": 11,
+ "line": "import signal\n",
+ "lineno": 11,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 11,
+ "start_region_line": 11
+ },
+ {
+ "end_outermost_loop": 12,
+ "end_region_line": 12,
+ "line": "\n",
+ "lineno": 12,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 12,
+ "start_region_line": 12
+ },
+ {
+ "end_outermost_loop": 13,
+ "end_region_line": 13,
+ "line": "# The code can be found in the following directory:\n",
+ "lineno": 13,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 13,
+ "start_region_line": 13
+ },
+ {
+ "end_outermost_loop": 14,
+ "end_region_line": 14,
+ "line": "# /opt/ros/melodic/lib/python2.7/dist-packages/dynamixel_sdk/\n",
+ "lineno": 14,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 14,
+ "start_region_line": 14
+ },
+ {
+ "end_outermost_loop": 15,
+ "end_region_line": 15,
+ "line": "import dynamixel_sdk.group_bulk_read as gbr\n",
+ "lineno": 15,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 15,
+ "start_region_line": 15
+ },
+ {
+ "end_outermost_loop": 16,
+ "end_region_line": 16,
+ "line": "import dynamixel_sdk.group_sync_read as gsr\n",
+ "lineno": 16,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 16,
+ "start_region_line": 16
+ },
+ {
+ "end_outermost_loop": 17,
+ "end_region_line": 17,
+ "line": "\n",
+ "lineno": 17,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 17,
+ "start_region_line": 17
+ },
+ {
+ "end_outermost_loop": 18,
+ "end_region_line": 18,
+ "line": "\n",
+ "lineno": 18,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 18,
+ "start_region_line": 18
+ },
+ {
+ "end_outermost_loop": 19,
+ "end_region_line": 19,
+ "line": "# #########################\n",
+ "lineno": 19,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 19,
+ "start_region_line": 19
+ },
+ {
+ "end_outermost_loop": 20,
+ "end_region_line": 20,
+ "line": "# XL430-W250\n",
+ "lineno": 20,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 20,
+ "start_region_line": 20
+ },
+ {
+ "end_outermost_loop": 21,
+ "end_region_line": 21,
+ "line": "# http://emanual.robotis.com/docs/en/dxl/x/xl430-w250/#control-table\n",
+ "lineno": 21,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 21,
+ "start_region_line": 21
+ },
+ {
+ "end_outermost_loop": 22,
+ "end_region_line": 22,
+ "line": "# XM540-W270\n",
+ "lineno": 22,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 22,
+ "start_region_line": 22
+ },
+ {
+ "end_outermost_loop": 23,
+ "end_region_line": 23,
+ "line": "# https://emanual.robotis.com/docs/en/dxl/x/xm540-w270/#control-table\n",
+ "lineno": 23,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 23,
+ "start_region_line": 23
+ },
+ {
+ "end_outermost_loop": 24,
+ "end_region_line": 24,
+ "line": "# xm430-w350\n",
+ "lineno": 24,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 24,
+ "start_region_line": 24
+ },
+ {
+ "end_outermost_loop": 25,
+ "end_region_line": 25,
+ "line": "#https://emanual.robotis.com/docs/en/dxl/x/xm430-w350/\n",
+ "lineno": 25,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 25,
+ "start_region_line": 25
+ },
+ {
+ "end_outermost_loop": 26,
+ "end_region_line": 26,
+ "line": "# xc430-w240\n",
+ "lineno": 26,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 26,
+ "start_region_line": 26
+ },
+ {
+ "end_outermost_loop": 27,
+ "end_region_line": 27,
+ "line": "#https://emanual.robotis.com/docs/en/dxl/x/xc430-w240/\n",
+ "lineno": 27,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 27,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 28,
+ "end_region_line": 28,
+ "line": "\n",
+ "lineno": 28,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 28,
+ "start_region_line": 28
+ },
+ {
+ "end_outermost_loop": 29,
+ "end_region_line": 29,
+ "line": "# Control table address\n",
+ "lineno": 29,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 29,
+ "start_region_line": 29
+ },
+ {
+ "end_outermost_loop": 30,
+ "end_region_line": 30,
+ "line": "#EEPROM\n",
+ "lineno": 30,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 30,
+ "start_region_line": 30
+ },
+ {
+ "end_outermost_loop": 31,
+ "end_region_line": 31,
+ "line": "XL430_ADDR_MODEL_NUMBER = 0\n",
+ "lineno": 31,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 31,
+ "start_region_line": 31
+ },
+ {
+ "end_outermost_loop": 32,
+ "end_region_line": 32,
+ "line": "XL430_ADDR_MODEL_INFORMATION = 2\n",
+ "lineno": 32,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 32,
+ "start_region_line": 32
+ },
+ {
+ "end_outermost_loop": 33,
+ "end_region_line": 33,
+ "line": "XL430_ADDR_FIRMWARE_VERSION = 6\n",
+ "lineno": 33,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 33,
+ "start_region_line": 33
+ },
+ {
+ "end_outermost_loop": 34,
+ "end_region_line": 34,
+ "line": "XL430_ADDR_ID = 7\n",
+ "lineno": 34,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 34,
+ "start_region_line": 34
+ },
+ {
+ "end_outermost_loop": 35,
+ "end_region_line": 35,
+ "line": "XL430_ADDR_BAUD_RATE = 8\n",
+ "lineno": 35,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 35,
+ "start_region_line": 35
+ },
+ {
+ "end_outermost_loop": 36,
+ "end_region_line": 36,
+ "line": "XL430_ADDR_RETURN_DELAY_TIME = 9\n",
+ "lineno": 36,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 36,
+ "start_region_line": 36
+ },
+ {
+ "end_outermost_loop": 37,
+ "end_region_line": 37,
+ "line": "XL430_ADDR_DRIVE_MODE = 10\n",
+ "lineno": 37,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 37,
+ "start_region_line": 37
+ },
+ {
+ "end_outermost_loop": 38,
+ "end_region_line": 38,
+ "line": "XL430_ADDR_OPERATING_MODE = 11\n",
+ "lineno": 38,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 38,
+ "start_region_line": 38
+ },
+ {
+ "end_outermost_loop": 39,
+ "end_region_line": 39,
+ "line": "XL430_ADDR_SECONDARY_ID = 12\n",
+ "lineno": 39,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 39,
+ "start_region_line": 39
+ },
+ {
+ "end_outermost_loop": 40,
+ "end_region_line": 40,
+ "line": "XL430_ADDR_PROTOCOL_VERSION =13\n",
+ "lineno": 40,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 40,
+ "start_region_line": 40
+ },
+ {
+ "end_outermost_loop": 41,
+ "end_region_line": 41,
+ "line": "XL430_ADDR_HOMING_OFFSET = 20\n",
+ "lineno": 41,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 41,
+ "start_region_line": 41
+ },
+ {
+ "end_outermost_loop": 42,
+ "end_region_line": 42,
+ "line": "XL430_ADDR_MOVING_THRESHOLD =24\n",
+ "lineno": 42,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 42,
+ "start_region_line": 42
+ },
+ {
+ "end_outermost_loop": 43,
+ "end_region_line": 43,
+ "line": "XL430_ADDR_TEMPERATURE_LIMIT = 31\n",
+ "lineno": 43,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 43,
+ "start_region_line": 43
+ },
+ {
+ "end_outermost_loop": 44,
+ "end_region_line": 44,
+ "line": "XL430_ADDR_MAX_VOLTAGE_LIMIT = 32\n",
+ "lineno": 44,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 44,
+ "start_region_line": 44
+ },
+ {
+ "end_outermost_loop": 45,
+ "end_region_line": 45,
+ "line": "XL430_ADDR_MIN_VOLTAGE_LIMIT = 34\n",
+ "lineno": 45,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 45,
+ "start_region_line": 45
+ },
+ {
+ "end_outermost_loop": 46,
+ "end_region_line": 46,
+ "line": "XL430_ADDR_PWM_LIMIT = 36\n",
+ "lineno": 46,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 46,
+ "start_region_line": 46
+ },
+ {
+ "end_outermost_loop": 47,
+ "end_region_line": 47,
+ "line": "XL430_ADDR_VELOCITY_LIMIT = 44\n",
+ "lineno": 47,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 47,
+ "start_region_line": 47
+ },
+ {
+ "end_outermost_loop": 48,
+ "end_region_line": 48,
+ "line": "XL430_ADDR_MAX_POS_LIMIT = 48\n",
+ "lineno": 48,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 48,
+ "start_region_line": 48
+ },
+ {
+ "end_outermost_loop": 49,
+ "end_region_line": 49,
+ "line": "XL430_ADDR_MIN_POS_LIMIT = 52\n",
+ "lineno": 49,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 49,
+ "start_region_line": 49
+ },
+ {
+ "end_outermost_loop": 50,
+ "end_region_line": 50,
+ "line": "XL430_ADDR_SHUTDOWN = 63\n",
+ "lineno": 50,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 50,
+ "start_region_line": 50
+ },
+ {
+ "end_outermost_loop": 51,
+ "end_region_line": 51,
+ "line": "\n",
+ "lineno": 51,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 51,
+ "start_region_line": 51
+ },
+ {
+ "end_outermost_loop": 52,
+ "end_region_line": 52,
+ "line": "#RAM\n",
+ "lineno": 52,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 52,
+ "start_region_line": 52
+ },
+ {
+ "end_outermost_loop": 53,
+ "end_region_line": 53,
+ "line": "XL430_ADDR_TORQUE_ENABLE = 64\n",
+ "lineno": 53,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 53,
+ "start_region_line": 53
+ },
+ {
+ "end_outermost_loop": 54,
+ "end_region_line": 54,
+ "line": "XL430_ADDR_LED = 65\n",
+ "lineno": 54,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 54,
+ "start_region_line": 54
+ },
+ {
+ "end_outermost_loop": 55,
+ "end_region_line": 55,
+ "line": "XL430_ADDR_STATUS_RETURN_LEVEL = 68\n",
+ "lineno": 55,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 55,
+ "start_region_line": 55
+ },
+ {
+ "end_outermost_loop": 56,
+ "end_region_line": 56,
+ "line": "XL430_ADDR_REGISTERED_INSTRUCTION = 69\n",
+ "lineno": 56,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 56,
+ "start_region_line": 56
+ },
+ {
+ "end_outermost_loop": 57,
+ "end_region_line": 57,
+ "line": "XL430_ADDR_HARDWARE_ERROR_STATUS = 70\n",
+ "lineno": 57,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 57,
+ "start_region_line": 57
+ },
+ {
+ "end_outermost_loop": 58,
+ "end_region_line": 58,
+ "line": "XL430_ADDR_VELOCITY_I_GAIN = 76\n",
+ "lineno": 58,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 58,
+ "start_region_line": 58
+ },
+ {
+ "end_outermost_loop": 59,
+ "end_region_line": 59,
+ "line": "XL430_ADDR_VELOCITY_P_GAIN = 78\n",
+ "lineno": 59,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 59,
+ "start_region_line": 59
+ },
+ {
+ "end_outermost_loop": 60,
+ "end_region_line": 60,
+ "line": "XL430_ADDR_POS_D_GAIN = 80\n",
+ "lineno": 60,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 60,
+ "start_region_line": 60
+ },
+ {
+ "end_outermost_loop": 61,
+ "end_region_line": 61,
+ "line": "XL430_ADDR_POS_I_GAIN = 82\n",
+ "lineno": 61,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 61,
+ "start_region_line": 61
+ },
+ {
+ "end_outermost_loop": 62,
+ "end_region_line": 62,
+ "line": "XL430_ADDR_POS_P_GAIN = 84\n",
+ "lineno": 62,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 62,
+ "start_region_line": 62
+ },
+ {
+ "end_outermost_loop": 63,
+ "end_region_line": 63,
+ "line": "XL430_ADDR_FF_2ND_GAIN = 88\n",
+ "lineno": 63,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 63,
+ "start_region_line": 63
+ },
+ {
+ "end_outermost_loop": 64,
+ "end_region_line": 64,
+ "line": "XL430_ADDR_FF_1ST_GAIN =90\n",
+ "lineno": 64,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 64,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 65,
+ "end_region_line": 65,
+ "line": "XL430_ADDR_BUS_WATCHDOG = 98\n",
+ "lineno": 65,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 65,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 66,
+ "end_region_line": 66,
+ "line": "XL430_ADDR_GOAL_PWM = 100\n",
+ "lineno": 66,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 66,
+ "start_region_line": 66
+ },
+ {
+ "end_outermost_loop": 67,
+ "end_region_line": 67,
+ "line": "XL430_ADDR_GOAL_VEL = 104\n",
+ "lineno": 67,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 67,
+ "start_region_line": 67
+ },
+ {
+ "end_outermost_loop": 68,
+ "end_region_line": 68,
+ "line": "XL430_ADDR_PROFILE_ACCELERATION = 108\n",
+ "lineno": 68,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 68,
+ "start_region_line": 68
+ },
+ {
+ "end_outermost_loop": 69,
+ "end_region_line": 69,
+ "line": "XL430_ADDR_PROFILE_VELOCITY = 112\n",
+ "lineno": 69,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 69,
+ "start_region_line": 69
+ },
+ {
+ "end_outermost_loop": 70,
+ "end_region_line": 70,
+ "line": "XL430_ADDR_GOAL_POSITION = 116\n",
+ "lineno": 70,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 70,
+ "start_region_line": 70
+ },
+ {
+ "end_outermost_loop": 71,
+ "end_region_line": 71,
+ "line": "XL430_ADDR_REALTIME_TICK = 120\n",
+ "lineno": 71,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 71,
+ "start_region_line": 71
+ },
+ {
+ "end_outermost_loop": 72,
+ "end_region_line": 72,
+ "line": "XL430_ADDR_MOVING = 122\n",
+ "lineno": 72,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 72,
+ "start_region_line": 72
+ },
+ {
+ "end_outermost_loop": 73,
+ "end_region_line": 73,
+ "line": "XL430_ADDR_MOVING_STATUS=123\n",
+ "lineno": 73,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 73,
+ "start_region_line": 73
+ },
+ {
+ "end_outermost_loop": 74,
+ "end_region_line": 74,
+ "line": "XL430_ADDR_PRESENT_PWM = 124\n",
+ "lineno": 74,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 74,
+ "start_region_line": 74
+ },
+ {
+ "end_outermost_loop": 75,
+ "end_region_line": 75,
+ "line": "XL430_ADDR_PRESENT_LOAD = 126\n",
+ "lineno": 75,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 75,
+ "start_region_line": 75
+ },
+ {
+ "end_outermost_loop": 76,
+ "end_region_line": 76,
+ "line": "XL430_ADDR_PRESENT_VELOCITY =128\n",
+ "lineno": 76,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 76,
+ "start_region_line": 76
+ },
+ {
+ "end_outermost_loop": 77,
+ "end_region_line": 77,
+ "line": "XL430_ADDR_PRESENT_POSITION = 132\n",
+ "lineno": 77,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 77,
+ "start_region_line": 77
+ },
+ {
+ "end_outermost_loop": 78,
+ "end_region_line": 78,
+ "line": "XL430_ADDR_VELOCITY_TRAJECTORY = 136\n",
+ "lineno": 78,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 78,
+ "start_region_line": 78
+ },
+ {
+ "end_outermost_loop": 79,
+ "end_region_line": 79,
+ "line": "XL430_ADDR_POSITION_TRAJECTORY=140\n",
+ "lineno": 79,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 79,
+ "start_region_line": 79
+ },
+ {
+ "end_outermost_loop": 80,
+ "end_region_line": 80,
+ "line": "XL430_ADDR_PRESENT_INPUT_VOLTATE = 144\n",
+ "lineno": 80,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 80,
+ "start_region_line": 80
+ },
+ {
+ "end_outermost_loop": 81,
+ "end_region_line": 81,
+ "line": "XL430_ADDR_PRESENT_TEMPERATURE = 146\n",
+ "lineno": 81,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 81,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 82,
+ "end_region_line": 82,
+ "line": "XL430_ADDR_HELLO_CALIBRATED = 661 #Appropriate Indirect Data 56 to store calibrated flag\n",
+ "lineno": 82,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 82,
+ "start_region_line": 82
+ },
+ {
+ "end_outermost_loop": 83,
+ "end_region_line": 83,
+ "line": "\n",
+ "lineno": 83,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 83,
+ "start_region_line": 83
+ },
+ {
+ "end_outermost_loop": 84,
+ "end_region_line": 84,
+ "line": "XM430_ADDR_GOAL_CURRENT = 102\n",
+ "lineno": 84,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 84,
+ "start_region_line": 84
+ },
+ {
+ "end_outermost_loop": 85,
+ "end_region_line": 85,
+ "line": "XM430_ADDR_CURRENT_LIMIT = 38\n",
+ "lineno": 85,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 85,
+ "start_region_line": 85
+ },
+ {
+ "end_outermost_loop": 86,
+ "end_region_line": 86,
+ "line": "XM430_ADDR_PRESENT_CURRENT = 126\n",
+ "lineno": 86,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 86,
+ "start_region_line": 86
+ },
+ {
+ "end_outermost_loop": 87,
+ "end_region_line": 87,
+ "line": "\n",
+ "lineno": 87,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 87,
+ "start_region_line": 87
+ },
+ {
+ "end_outermost_loop": 88,
+ "end_region_line": 88,
+ "line": "COMM_CODES = {\n",
+ "lineno": 88,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 88,
+ "start_region_line": 88
+ },
+ {
+ "end_outermost_loop": 89,
+ "end_region_line": 89,
+ "line": " COMM_SUCCESS: \"COMM_SUCCESS\",\n",
+ "lineno": 89,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 89,
+ "start_region_line": 89
+ },
+ {
+ "end_outermost_loop": 90,
+ "end_region_line": 90,
+ "line": " COMM_PORT_BUSY: \"COMM_PORT_BUSY\",\n",
+ "lineno": 90,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 90,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 91,
+ "end_region_line": 91,
+ "line": " COMM_TX_FAIL: \"COMM_TX_FAIL\",\n",
+ "lineno": 91,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 91,
+ "start_region_line": 91
+ },
+ {
+ "end_outermost_loop": 92,
+ "end_region_line": 92,
+ "line": " COMM_RX_FAIL: \"COMM_RX_FAIL\",\n",
+ "lineno": 92,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 92,
+ "start_region_line": 92
+ },
+ {
+ "end_outermost_loop": 93,
+ "end_region_line": 93,
+ "line": " COMM_TX_ERROR: \"COMM_TX_ERROR\",\n",
+ "lineno": 93,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 93,
+ "start_region_line": 93
+ },
+ {
+ "end_outermost_loop": 94,
+ "end_region_line": 94,
+ "line": " COMM_RX_WAITING: \"COMM_RX_WAITING\",\n",
+ "lineno": 94,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 94,
+ "start_region_line": 94
+ },
+ {
+ "end_outermost_loop": 95,
+ "end_region_line": 95,
+ "line": " COMM_RX_TIMEOUT: \"COMM_RX_TIMEOUT\",\n",
+ "lineno": 95,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 95,
+ "start_region_line": 95
+ },
+ {
+ "end_outermost_loop": 96,
+ "end_region_line": 96,
+ "line": " COMM_RX_CORRUPT: \"COMM_RX_CORRUPT\",\n",
+ "lineno": 96,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 96,
+ "start_region_line": 96
+ },
+ {
+ "end_outermost_loop": 97,
+ "end_region_line": 97,
+ "line": " COMM_NOT_AVAILABLE: \"COMM_NOT_AVAILABLE\"\n",
+ "lineno": 97,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 97,
+ "start_region_line": 97
+ },
+ {
+ "end_outermost_loop": 98,
+ "end_region_line": 98,
+ "line": "}\n",
+ "lineno": 98,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 98,
+ "start_region_line": 98
+ },
+ {
+ "end_outermost_loop": 99,
+ "end_region_line": 99,
+ "line": "\n",
+ "lineno": 99,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 99,
+ "start_region_line": 99
+ },
+ {
+ "end_outermost_loop": 100,
+ "end_region_line": 100,
+ "line": "BAUD_MAP = {\n",
+ "lineno": 100,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 100,
+ "start_region_line": 100
+ },
+ {
+ "end_outermost_loop": 101,
+ "end_region_line": 101,
+ "line": " 9600: 0,\n",
+ "lineno": 101,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 101,
+ "start_region_line": 101
+ },
+ {
+ "end_outermost_loop": 102,
+ "end_region_line": 102,
+ "line": " 57600: 1,\n",
+ "lineno": 102,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 102,
+ "start_region_line": 102
+ },
+ {
+ "end_outermost_loop": 103,
+ "end_region_line": 103,
+ "line": " 115200: 2,\n",
+ "lineno": 103,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 103,
+ "start_region_line": 103
+ },
+ {
+ "end_outermost_loop": 104,
+ "end_region_line": 104,
+ "line": " 1000000: 3,\n",
+ "lineno": 104,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 104,
+ "start_region_line": 104
+ },
+ {
+ "end_outermost_loop": 105,
+ "end_region_line": 105,
+ "line": " 2000000: 4,\n",
+ "lineno": 105,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 105,
+ "start_region_line": 105
+ },
+ {
+ "end_outermost_loop": 106,
+ "end_region_line": 106,
+ "line": " 3000000: 5,\n",
+ "lineno": 106,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 106,
+ "start_region_line": 106
+ },
+ {
+ "end_outermost_loop": 107,
+ "end_region_line": 107,
+ "line": " 4000000: 6,\n",
+ "lineno": 107,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 107,
+ "start_region_line": 107
+ },
+ {
+ "end_outermost_loop": 108,
+ "end_region_line": 108,
+ "line": " 4500000: 7\n",
+ "lineno": 108,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 108,
+ "start_region_line": 108
+ },
+ {
+ "end_outermost_loop": 109,
+ "end_region_line": 109,
+ "line": "}\n",
+ "lineno": 109,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 109,
+ "start_region_line": 109
+ },
+ {
+ "end_outermost_loop": 110,
+ "end_region_line": 110,
+ "line": "\n",
+ "lineno": 110,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 110,
+ "start_region_line": 110
+ },
+ {
+ "end_outermost_loop": 111,
+ "end_region_line": 111,
+ "line": "MODEL_NUMBERS = {1080: 'XC430-W240', 1120:'XM540-W270',1060:'XL430-W250',1020:'XM430-W350'}\n",
+ "lineno": 111,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 111,
+ "start_region_line": 111
+ },
+ {
+ "end_outermost_loop": 112,
+ "end_region_line": 112,
+ "line": "\n",
+ "lineno": 112,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 112,
+ "start_region_line": 112
+ },
+ {
+ "end_outermost_loop": 131,
+ "end_region_line": 131,
+ "line": "class DelayedKeyboardInterrupt:\n",
+ "lineno": 113,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 113,
+ "start_region_line": 113
+ },
+ {
+ "end_outermost_loop": 114,
+ "end_region_line": 131,
+ "line": "\n",
+ "lineno": 114,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 114,
+ "start_region_line": 113
+ },
+ {
+ "end_outermost_loop": 120,
+ "end_region_line": 120,
+ "line": " def __enter__(self):\n",
+ "lineno": 115,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 115,
+ "start_region_line": 115
+ },
+ {
+ "end_outermost_loop": 116,
+ "end_region_line": 120,
+ "line": " self.signal_received = False\n",
+ "lineno": 116,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 116,
+ "start_region_line": 115
+ },
+ {
+ "end_outermost_loop": 117,
+ "end_region_line": 120,
+ "line": " try:\n",
+ "lineno": 117,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 115
+ },
+ {
+ "end_outermost_loop": 118,
+ "end_region_line": 120,
+ "line": " self.old_handler = signal.signal(signal.SIGINT, self.handler)\n",
+ "lineno": 118,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 118,
+ "start_region_line": 115
+ },
+ {
+ "end_outermost_loop": 119,
+ "end_region_line": 120,
+ "line": " except ValueError:\n",
+ "lineno": 119,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 119,
+ "start_region_line": 115
+ },
+ {
+ "end_outermost_loop": 120,
+ "end_region_line": 120,
+ "line": " pass\n",
+ "lineno": 120,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 120,
+ "start_region_line": 115
+ },
+ {
+ "end_outermost_loop": 121,
+ "end_region_line": 131,
+ "line": "\n",
+ "lineno": 121,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 121,
+ "start_region_line": 113
+ },
+ {
+ "end_outermost_loop": 123,
+ "end_region_line": 123,
+ "line": " def handler(self, sig, frame):\n",
+ "lineno": 122,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 122,
+ "start_region_line": 122
+ },
+ {
+ "end_outermost_loop": 123,
+ "end_region_line": 123,
+ "line": " self.signal_received = (sig, frame)\n",
+ "lineno": 123,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 123,
+ "start_region_line": 122
+ },
+ {
+ "end_outermost_loop": 124,
+ "end_region_line": 131,
+ "line": "\n",
+ "lineno": 124,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 124,
+ "start_region_line": 113
+ },
+ {
+ "end_outermost_loop": 131,
+ "end_region_line": 131,
+ "line": " def __exit__(self, type, value, traceback):\n",
+ "lineno": 125,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 125,
+ "start_region_line": 125
+ },
+ {
+ "end_outermost_loop": 126,
+ "end_region_line": 131,
+ "line": " try:\n",
+ "lineno": 126,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 126,
+ "start_region_line": 125
+ },
+ {
+ "end_outermost_loop": 127,
+ "end_region_line": 131,
+ "line": " signal.signal(signal.SIGINT, self.old_handler)\n",
+ "lineno": 127,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 127,
+ "start_region_line": 125
+ },
+ {
+ "end_outermost_loop": 129,
+ "end_region_line": 131,
+ "line": " if self.signal_received:\n",
+ "lineno": 128,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 128,
+ "start_region_line": 125
+ },
+ {
+ "end_outermost_loop": 129,
+ "end_region_line": 131,
+ "line": " self.old_handler(*self.signal_received)\n",
+ "lineno": 129,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 129,
+ "start_region_line": 125
+ },
+ {
+ "end_outermost_loop": 130,
+ "end_region_line": 131,
+ "line": " except (ValueError,AttributeError):\n",
+ "lineno": 130,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 130,
+ "start_region_line": 125
+ },
+ {
+ "end_outermost_loop": 131,
+ "end_region_line": 131,
+ "line": " pass\n",
+ "lineno": 131,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 131,
+ "start_region_line": 125
+ },
+ {
+ "end_outermost_loop": 132,
+ "end_region_line": 132,
+ "line": "\n",
+ "lineno": 132,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 132,
+ "start_region_line": 132
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": "class DynamixelCommError(Exception):\n",
+ "lineno": 133,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 133,
+ "start_region_line": 133
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": " pass\n",
+ "lineno": 134,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 134,
+ "start_region_line": 133
+ },
+ {
+ "end_outermost_loop": 135,
+ "end_region_line": 135,
+ "line": "\n",
+ "lineno": 135,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 135,
+ "start_region_line": 135
+ },
+ {
+ "end_outermost_loop": 136,
+ "end_region_line": 136,
+ "line": "\n",
+ "lineno": 136,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 136,
+ "start_region_line": 136
+ },
+ {
+ "end_outermost_loop": 1035,
+ "end_region_line": 1035,
+ "line": "class DynamixelXL430():\n",
+ "lineno": 137,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 137,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 138,
+ "end_region_line": 1035,
+ "line": " \"\"\"\n",
+ "lineno": 138,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 138,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 139,
+ "end_region_line": 1035,
+ "line": " Wrapping of Dynamixel X-Series interface\n",
+ "lineno": 139,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 139,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 140,
+ "end_region_line": 1035,
+ "line": " \"\"\"\n",
+ "lineno": 140,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 140,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 155,
+ "end_region_line": 155,
+ "line": " def __init__(self, dxl_id, usb, port_handler=None, pt_lock=None, baud=115200, logger=logging.getLogger()):\n",
+ "lineno": 141,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 141,
+ "start_region_line": 141
+ },
+ {
+ "end_outermost_loop": 142,
+ "end_region_line": 155,
+ "line": " self.dxl_id = dxl_id\n",
+ "lineno": 142,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 142,
+ "start_region_line": 141
+ },
+ {
+ "end_outermost_loop": 143,
+ "end_region_line": 155,
+ "line": " self.usb = usb\n",
+ "lineno": 143,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 143,
+ "start_region_line": 141
+ },
+ {
+ "end_outermost_loop": 144,
+ "end_region_line": 155,
+ "line": " self.comm_errors = 0\n",
+ "lineno": 144,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 144,
+ "start_region_line": 141
+ },
+ {
+ "end_outermost_loop": 145,
+ "end_region_line": 155,
+ "line": " self.last_comm_success = True\n",
+ "lineno": 145,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 145,
+ "start_region_line": 141
+ },
+ {
+ "end_outermost_loop": 146,
+ "end_region_line": 155,
+ "line": " self.logger = logger\n",
+ "lineno": 146,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 146,
+ "start_region_line": 141
+ },
+ {
+ "end_outermost_loop": 147,
+ "end_region_line": 155,
+ "line": " self.baud=baud\n",
+ "lineno": 147,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 147,
+ "start_region_line": 141
+ },
+ {
+ "end_outermost_loop": 148,
+ "end_region_line": 155,
+ "line": " self.dxl_model_name=''\n",
+ "lineno": 148,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 148,
+ "start_region_line": 141
+ },
+ {
+ "end_outermost_loop": 155,
+ "end_region_line": 155,
+ "line": " # Make access to portHandler threadsafe\n",
+ "lineno": 149,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 141,
+ "start_region_line": 141
+ },
+ {
+ "end_outermost_loop": 150,
+ "end_region_line": 155,
+ "line": " self.pt_lock = threading.RLock() if pt_lock is None else pt_lock\n",
+ "lineno": 150,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 150,
+ "start_region_line": 141
+ },
+ {
+ "end_outermost_loop": 151,
+ "end_region_line": 155,
+ "line": " self.hw_valid = False\n",
+ "lineno": 151,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 151,
+ "start_region_line": 141
+ },
+ {
+ "end_outermost_loop": 152,
+ "end_region_line": 155,
+ "line": "\n",
+ "lineno": 152,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 152,
+ "start_region_line": 141
+ },
+ {
+ "end_outermost_loop": 155,
+ "end_region_line": 155,
+ "line": " # Allow sharing of port handler across multiple servos\n",
+ "lineno": 153,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 141,
+ "start_region_line": 141
+ },
+ {
+ "end_outermost_loop": 154,
+ "end_region_line": 155,
+ "line": " self.port_handler = port_handler\n",
+ "lineno": 154,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 154,
+ "start_region_line": 141
+ },
+ {
+ "end_outermost_loop": 155,
+ "end_region_line": 155,
+ "line": " self.packet_handler= None\n",
+ "lineno": 155,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 155,
+ "start_region_line": 141
+ },
+ {
+ "end_outermost_loop": 156,
+ "end_region_line": 1035,
+ "line": " \n",
+ "lineno": 156,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 156,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 168,
+ "end_region_line": 168,
+ "line": " def create_port_handler(self):\n",
+ "lineno": 157,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 157,
+ "start_region_line": 157
+ },
+ {
+ "end_outermost_loop": 158,
+ "end_region_line": 168,
+ "line": " try:\n",
+ "lineno": 158,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 158,
+ "start_region_line": 157
+ },
+ {
+ "end_outermost_loop": 164,
+ "end_region_line": 168,
+ "line": " if self.port_handler is None or not self.port_handler.is_open:\n",
+ "lineno": 159,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 159,
+ "start_region_line": 157
+ },
+ {
+ "end_outermost_loop": 160,
+ "end_region_line": 168,
+ "line": " self.port_handler = prh.PortHandler(self.usb)\n",
+ "lineno": 160,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 160,
+ "start_region_line": 157
+ },
+ {
+ "end_outermost_loop": 161,
+ "end_region_line": 168,
+ "line": " self.port_handler.openPort()\n",
+ "lineno": 161,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 161,
+ "start_region_line": 157
+ },
+ {
+ "end_outermost_loop": 162,
+ "end_region_line": 168,
+ "line": " self.port_handler.setBaudRate(self.baud)\n",
+ "lineno": 162,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 162,
+ "start_region_line": 157
+ },
+ {
+ "end_outermost_loop": 164,
+ "end_region_line": 168,
+ "line": " else:\n",
+ "lineno": 163,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 159,
+ "start_region_line": 157
+ },
+ {
+ "end_outermost_loop": 164,
+ "end_region_line": 168,
+ "line": " self.port_handler = self.port_handler\n",
+ "lineno": 164,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 164,
+ "start_region_line": 157
+ },
+ {
+ "end_outermost_loop": 165,
+ "end_region_line": 168,
+ "line": " self.packet_handler = pch.PacketHandler(2.0)\n",
+ "lineno": 165,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 165,
+ "start_region_line": 157
+ },
+ {
+ "end_outermost_loop": 166,
+ "end_region_line": 168,
+ "line": " except serial.SerialException as e:\n",
+ "lineno": 166,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 166,
+ "start_region_line": 157
+ },
+ {
+ "end_outermost_loop": 167,
+ "end_region_line": 168,
+ "line": " self.logger.error(\"Dynamixel SerialException({1}): {2}\".format(self.usb,e.errno, e.strerror))\n",
+ "lineno": 167,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 167,
+ "start_region_line": 157
+ },
+ {
+ "end_outermost_loop": 168,
+ "end_region_line": 168,
+ "line": " self.hw_valid = self.packet_handler is not None\n",
+ "lineno": 168,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 168,
+ "start_region_line": 157
+ },
+ {
+ "end_outermost_loop": 169,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 169,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 169,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 1035,
+ "end_region_line": 1035,
+ "line": " @staticmethod\n",
+ "lineno": 170,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 137,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 198,
+ "end_region_line": 198,
+ "line": " def identify_baud_rate(dxl_id, usb):\n",
+ "lineno": 171,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 171,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 172,
+ "end_region_line": 198,
+ "line": " \"\"\"Identify the baud rate a Dynamixel servo is communicating at.\n",
+ "lineno": 172,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 172,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 173,
+ "end_region_line": 198,
+ "line": "\n",
+ "lineno": 173,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 173,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 174,
+ "end_region_line": 198,
+ "line": " Parameters\n",
+ "lineno": 174,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 174,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 175,
+ "end_region_line": 198,
+ "line": " ----------\n",
+ "lineno": 175,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 175,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 176,
+ "end_region_line": 198,
+ "line": " dxl_id : int\n",
+ "lineno": 176,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 176,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 177,
+ "end_region_line": 198,
+ "line": " Dynamixel ID on chain. Must be [0, 25]\n",
+ "lineno": 177,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 177,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 178,
+ "end_region_line": 198,
+ "line": " usb : str\n",
+ "lineno": 178,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 178,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 179,
+ "end_region_line": 198,
+ "line": " the USB port, typically \"/dev/something\"\n",
+ "lineno": 179,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 179,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 180,
+ "end_region_line": 198,
+ "line": "\n",
+ "lineno": 180,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 180,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 181,
+ "end_region_line": 198,
+ "line": " Returns\n",
+ "lineno": 181,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 181,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 182,
+ "end_region_line": 198,
+ "line": " -------\n",
+ "lineno": 182,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 182,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 183,
+ "end_region_line": 198,
+ "line": " int\n",
+ "lineno": 183,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 183,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 184,
+ "end_region_line": 198,
+ "line": " the baud rate the Dynamixel is communicating at\n",
+ "lineno": 184,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 184,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 185,
+ "end_region_line": 198,
+ "line": " \"\"\"\n",
+ "lineno": 185,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 185,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 186,
+ "end_region_line": 198,
+ "line": " try:\n",
+ "lineno": 186,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 186,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 195,
+ "end_region_line": 195,
+ "line": " for b in BAUD_MAP.keys():\n",
+ "lineno": 187,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 187,
+ "start_region_line": 187
+ },
+ {
+ "end_outermost_loop": 195,
+ "end_region_line": 195,
+ "line": " port_h = prh.PortHandler(usb)\n",
+ "lineno": 188,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 187,
+ "start_region_line": 187
+ },
+ {
+ "end_outermost_loop": 195,
+ "end_region_line": 195,
+ "line": " port_h.openPort()\n",
+ "lineno": 189,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 187,
+ "start_region_line": 187
+ },
+ {
+ "end_outermost_loop": 195,
+ "end_region_line": 195,
+ "line": " port_h.setBaudRate(b)\n",
+ "lineno": 190,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 187,
+ "start_region_line": 187
+ },
+ {
+ "end_outermost_loop": 195,
+ "end_region_line": 195,
+ "line": " packet_h = pch.PacketHandler(2.0)\n",
+ "lineno": 191,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 187,
+ "start_region_line": 187
+ },
+ {
+ "end_outermost_loop": 195,
+ "end_region_line": 195,
+ "line": " _, dxl_comm_result, _ = packet_h.ping(port_h, dxl_id)\n",
+ "lineno": 192,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 187,
+ "start_region_line": 187
+ },
+ {
+ "end_outermost_loop": 195,
+ "end_region_line": 195,
+ "line": " port_h.closePort()\n",
+ "lineno": 193,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 187,
+ "start_region_line": 187
+ },
+ {
+ "end_outermost_loop": 195,
+ "end_region_line": 195,
+ "line": " if dxl_comm_result == COMM_SUCCESS:\n",
+ "lineno": 194,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 187,
+ "start_region_line": 187
+ },
+ {
+ "end_outermost_loop": 195,
+ "end_region_line": 195,
+ "line": " return b\n",
+ "lineno": 195,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 187,
+ "start_region_line": 187
+ },
+ {
+ "end_outermost_loop": 196,
+ "end_region_line": 198,
+ "line": " except:\n",
+ "lineno": 196,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 196,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 197,
+ "end_region_line": 198,
+ "line": " pass\n",
+ "lineno": 197,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 197,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 198,
+ "end_region_line": 198,
+ "line": " return -1\n",
+ "lineno": 198,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 198,
+ "start_region_line": 171
+ },
+ {
+ "end_outermost_loop": 199,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 199,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 199,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 214,
+ "end_region_line": 214,
+ "line": " def startup(self):\n",
+ "lineno": 200,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 200,
+ "start_region_line": 200
+ },
+ {
+ "end_outermost_loop": 201,
+ "end_region_line": 214,
+ "line": " self.create_port_handler()\n",
+ "lineno": 201,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 201,
+ "start_region_line": 200
+ },
+ {
+ "end_outermost_loop": 213,
+ "end_region_line": 214,
+ "line": " if self.hw_valid:\n",
+ "lineno": 202,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 202,
+ "start_region_line": 200
+ },
+ {
+ "end_outermost_loop": 203,
+ "end_region_line": 214,
+ "line": " try:\n",
+ "lineno": 203,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 203,
+ "start_region_line": 200
+ },
+ {
+ "end_outermost_loop": 204,
+ "end_region_line": 214,
+ "line": " self.enable_torque()\n",
+ "lineno": 204,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 204,
+ "start_region_line": 200
+ },
+ {
+ "end_outermost_loop": 205,
+ "end_region_line": 214,
+ "line": " except DynamixelCommError:\n",
+ "lineno": 205,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 205,
+ "start_region_line": 200
+ },
+ {
+ "end_outermost_loop": 206,
+ "end_region_line": 214,
+ "line": " baud=self.identify_baud_rate(self.dxl_id,self.usb)\n",
+ "lineno": 206,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 206,
+ "start_region_line": 200
+ },
+ {
+ "end_outermost_loop": 210,
+ "end_region_line": 214,
+ "line": " if baud!=self.baud:\n",
+ "lineno": 207,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 207,
+ "start_region_line": 200
+ },
+ {
+ "end_outermost_loop": 208,
+ "end_region_line": 214,
+ "line": " self.logger.error('DynamixelCommError. Mismatched baud rate. Expected %d but servo is set to %d.'%(self.baud,baud))\n",
+ "lineno": 208,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 208,
+ "start_region_line": 200
+ },
+ {
+ "end_outermost_loop": 210,
+ "end_region_line": 214,
+ "line": " else:\n",
+ "lineno": 209,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 207,
+ "start_region_line": 200
+ },
+ {
+ "end_outermost_loop": 210,
+ "end_region_line": 214,
+ "line": " self.logger.error('DynamixelCommError. Failed to startup servo %s at id %d . Check that id and usb bus are valid'%(self.usb,self.dxl_id))\n",
+ "lineno": 210,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 210,
+ "start_region_line": 200
+ },
+ {
+ "end_outermost_loop": 211,
+ "end_region_line": 214,
+ "line": " self.hw_valid=False\n",
+ "lineno": 211,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 211,
+ "start_region_line": 200
+ },
+ {
+ "end_outermost_loop": 212,
+ "end_region_line": 214,
+ "line": " return False\n",
+ "lineno": 212,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 212,
+ "start_region_line": 200
+ },
+ {
+ "end_outermost_loop": 213,
+ "end_region_line": 214,
+ "line": " return True\n",
+ "lineno": 213,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 213,
+ "start_region_line": 200
+ },
+ {
+ "end_outermost_loop": 214,
+ "end_region_line": 214,
+ "line": " return False\n",
+ "lineno": 214,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 214,
+ "start_region_line": 200
+ },
+ {
+ "end_outermost_loop": 215,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 215,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 215,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 216,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 216,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 216,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 223,
+ "end_region_line": 223,
+ "line": " def stop(self, close_port=True, disable_torque=False):\n",
+ "lineno": 217,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 217,
+ "start_region_line": 217
+ },
+ {
+ "end_outermost_loop": 223,
+ "end_region_line": 223,
+ "line": " if self.hw_valid:\n",
+ "lineno": 218,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 218,
+ "start_region_line": 217
+ },
+ {
+ "end_outermost_loop": 219,
+ "end_region_line": 223,
+ "line": " self.hw_valid = False\n",
+ "lineno": 219,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 219,
+ "start_region_line": 217
+ },
+ {
+ "end_outermost_loop": 221,
+ "end_region_line": 223,
+ "line": " if disable_torque:\n",
+ "lineno": 220,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 220,
+ "start_region_line": 217
+ },
+ {
+ "end_outermost_loop": 221,
+ "end_region_line": 223,
+ "line": " self.disable_torque()\n",
+ "lineno": 221,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 221,
+ "start_region_line": 217
+ },
+ {
+ "end_outermost_loop": 223,
+ "end_region_line": 223,
+ "line": " if close_port:\n",
+ "lineno": 222,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 222,
+ "start_region_line": 217
+ },
+ {
+ "end_outermost_loop": 223,
+ "end_region_line": 223,
+ "line": " self.port_handler.closePort()\n",
+ "lineno": 223,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 223,
+ "start_region_line": 217
+ },
+ {
+ "end_outermost_loop": 224,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 224,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 224,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 250,
+ "end_region_line": 250,
+ "line": " def pretty_print(self):\n",
+ "lineno": 225,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 225,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 226,
+ "end_region_line": 250,
+ "line": " h = self.get_hardware_error()\n",
+ "lineno": 226,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 226,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 227,
+ "end_region_line": 250,
+ "line": " status = {\n",
+ "lineno": 227,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 227,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 228,
+ "end_region_line": 250,
+ "line": " 'ID:': self.get_id(),\n",
+ "lineno": 228,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 228,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 229,
+ "end_region_line": 250,
+ "line": " 'Operating Mode:': self.get_operating_mode(),\n",
+ "lineno": 229,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 229,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 230,
+ "end_region_line": 250,
+ "line": " 'Drive Mode:': format(self.get_drive_mode(), '#010b'),\n",
+ "lineno": 230,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 230,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 231,
+ "end_region_line": 250,
+ "line": " 'Temperature:': f'{self.get_temp()} \u00b0C',\n",
+ "lineno": 231,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 231,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 232,
+ "end_region_line": 250,
+ "line": " 'Position:': f'{self.get_pos()} ticks',\n",
+ "lineno": 232,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 232,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 233,
+ "end_region_line": 250,
+ "line": " 'Velocity:': f'{self.get_vel() * 0.229:.3f} rev/min',\n",
+ "lineno": 233,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 233,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 234,
+ "end_region_line": 250,
+ "line": " 'Load:': f'{self.get_load() * 0.1:.3f} %',\n",
+ "lineno": 234,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 234,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 235,
+ "end_region_line": 250,
+ "line": " 'PWM:': f'{self.get_pwm() * 0.113:.3f} %',\n",
+ "lineno": 235,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 235,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 236,
+ "end_region_line": 250,
+ "line": " 'Is Moving:': str(self.is_moving() != 0),\n",
+ "lineno": 236,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 236,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 237,
+ "end_region_line": 250,
+ "line": " 'Is Calibrated:': str(self.is_calibrated() != 0),\n",
+ "lineno": 237,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 237,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 238,
+ "end_region_line": 250,
+ "line": " 'Profile Velocity:': f'{self.get_profile_velocity() * 0.299:.3f} rev/min',\n",
+ "lineno": 238,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 238,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 239,
+ "end_region_line": 250,
+ "line": " 'Profile Acceleration:': f'{self.get_profile_acceleration() * 214.577:.3f} rev/min^2',\n",
+ "lineno": 239,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 239,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 240,
+ "end_region_line": 250,
+ "line": " 'Hardware Error Status:': format(h, '#010b'),\n",
+ "lineno": 240,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 240,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 241,
+ "end_region_line": 250,
+ "line": " ' Input Voltage Error:': str(h \\u0026 1 != 0),\n",
+ "lineno": 241,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 241,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 242,
+ "end_region_line": 250,
+ "line": " ' Overheating Error: ': str(h \\u0026 4 != 0),\n",
+ "lineno": 242,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 242,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 243,
+ "end_region_line": 250,
+ "line": " ' Motor Encoder Error:': str(h \\u0026 8 != 0),\n",
+ "lineno": 243,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 243,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 244,
+ "end_region_line": 250,
+ "line": " ' Electrical Shock Error:': str(h \\u0026 16 != 0),\n",
+ "lineno": 244,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 244,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 245,
+ "end_region_line": 250,
+ "line": " ' Overload Error:': str(h \\u0026 32 != 0),\n",
+ "lineno": 245,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 245,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 246,
+ "end_region_line": 250,
+ "line": " '# Communication Errors:': self.comm_errors,\n",
+ "lineno": 246,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 246,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 247,
+ "end_region_line": 250,
+ "line": " }\n",
+ "lineno": 247,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 247,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 248,
+ "end_region_line": 250,
+ "line": " print('------------------- XL430 -------------------')\n",
+ "lineno": 248,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 248,
+ "start_region_line": 225
+ },
+ {
+ "end_outermost_loop": 250,
+ "end_region_line": 250,
+ "line": " for elem, value in status.items():\n",
+ "lineno": 249,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 249,
+ "start_region_line": 249
+ },
+ {
+ "end_outermost_loop": 250,
+ "end_region_line": 250,
+ "line": " print(f\"{elem: \\u003c25}{value: \\u003e20}\")\n",
+ "lineno": 250,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 249,
+ "start_region_line": 249
+ },
+ {
+ "end_outermost_loop": 251,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 251,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 251,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 1035,
+ "end_region_line": 1035,
+ "line": " # ##########################################\n",
+ "lineno": 252,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 137,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 253,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 253,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 253,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 279,
+ "end_region_line": 279,
+ "line": " def handle_comm_result(self, fx, dxl_comm_result, dxl_error):\n",
+ "lineno": 254,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 254,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 255,
+ "end_region_line": 279,
+ "line": " \"\"\"Handles comm result and tracks comm errors.\n",
+ "lineno": 255,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 255,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 256,
+ "end_region_line": 279,
+ "line": "\n",
+ "lineno": 256,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 256,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 257,
+ "end_region_line": 279,
+ "line": " Parameters\n",
+ "lineno": 257,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 257,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 258,
+ "end_region_line": 279,
+ "line": " ----------\n",
+ "lineno": 258,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 258,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 259,
+ "end_region_line": 279,
+ "line": " fx : str\n",
+ "lineno": 259,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 259,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 260,
+ "end_region_line": 279,
+ "line": " control table address label\n",
+ "lineno": 260,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 260,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 261,
+ "end_region_line": 279,
+ "line": " dxl_comm_result : int\n",
+ "lineno": 261,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 261,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 262,
+ "end_region_line": 279,
+ "line": " communication result from options `COMM_CODES`\n",
+ "lineno": 262,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 262,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 263,
+ "end_region_line": 279,
+ "line": " dxl_error : int\n",
+ "lineno": 263,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 263,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 264,
+ "end_region_line": 279,
+ "line": " hardware errors sent by the dynamixel\n",
+ "lineno": 264,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 264,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 265,
+ "end_region_line": 279,
+ "line": "\n",
+ "lineno": 265,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 265,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 266,
+ "end_region_line": 279,
+ "line": " Returns\n",
+ "lineno": 266,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 266,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 267,
+ "end_region_line": 279,
+ "line": " -------\n",
+ "lineno": 267,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 267,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 268,
+ "end_region_line": 279,
+ "line": " bool\n",
+ "lineno": 268,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 268,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 269,
+ "end_region_line": 279,
+ "line": " True if successful result, False otherwise\n",
+ "lineno": 269,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 269,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 270,
+ "end_region_line": 279,
+ "line": " \"\"\"\n",
+ "lineno": 270,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 270,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 273,
+ "end_region_line": 279,
+ "line": " if dxl_comm_result==COMM_SUCCESS:\n",
+ "lineno": 271,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 271,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 272,
+ "end_region_line": 279,
+ "line": " self.last_comm_success=True\n",
+ "lineno": 272,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 272,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 273,
+ "end_region_line": 279,
+ "line": " return True\n",
+ "lineno": 273,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 273,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 274,
+ "end_region_line": 279,
+ "line": "\n",
+ "lineno": 274,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 274,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 275,
+ "end_region_line": 279,
+ "line": " self.last_comm_success = False\n",
+ "lineno": 275,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 275,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 276,
+ "end_region_line": 279,
+ "line": " self.comm_errors += 1\n",
+ "lineno": 276,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 276,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 277,
+ "end_region_line": 279,
+ "line": " comm_error_msg = f'DXL Comm Error on {self.usb} ID {self.dxl_id}. Attempted {fx}. Result {COMM_CODES[dxl_comm_result]}. Error {dxl_error}. Total Errors {self.comm_errors}.'\n",
+ "lineno": 277,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 277,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 278,
+ "end_region_line": 279,
+ "line": " self.logger.debug(comm_error_msg)\n",
+ "lineno": 278,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 278,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 279,
+ "end_region_line": 279,
+ "line": " raise DynamixelCommError(comm_error_msg)\n",
+ "lineno": 279,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 279,
+ "start_region_line": 254
+ },
+ {
+ "end_outermost_loop": 280,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 280,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 280,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 281,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 281,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 281,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 283,
+ "end_region_line": 283,
+ "line": " def get_comm_errors(self):\n",
+ "lineno": 282,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 282,
+ "start_region_line": 282
+ },
+ {
+ "end_outermost_loop": 283,
+ "end_region_line": 283,
+ "line": " return self.comm_errors\n",
+ "lineno": 283,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 283,
+ "start_region_line": 282
+ },
+ {
+ "end_outermost_loop": 284,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 284,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 284,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 290,
+ "end_region_line": 290,
+ "line": " def read_int32_t(self,addr):\n",
+ "lineno": 285,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 285,
+ "start_region_line": 285
+ },
+ {
+ "end_outermost_loop": 288,
+ "end_region_line": 290,
+ "line": " with self.pt_lock:\n",
+ "lineno": 286,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 286,
+ "start_region_line": 285
+ },
+ {
+ "end_outermost_loop": 288,
+ "end_region_line": 290,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 287,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 287,
+ "start_region_line": 285
+ },
+ {
+ "end_outermost_loop": 288,
+ "end_region_line": 290,
+ "line": " x, dxl_comm_result, dxl_error = self.packet_handler.read4ByteTxRx(self.port_handler, self.dxl_id, addr)\n",
+ "lineno": 288,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 288,
+ "start_region_line": 285
+ },
+ {
+ "end_outermost_loop": 289,
+ "end_region_line": 290,
+ "line": " xn = struct.unpack('i', arr.array('B',[DXL_LOBYTE(DXL_LOWORD(x)), DXL_HIBYTE(DXL_LOWORD(x)), DXL_LOBYTE(DXL_HIWORD(x)),DXL_HIBYTE(DXL_HIWORD(x))]))[0]\n",
+ "lineno": 289,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 289,
+ "start_region_line": 285
+ },
+ {
+ "end_outermost_loop": 290,
+ "end_region_line": 290,
+ "line": " return xn, dxl_comm_result, dxl_error\n",
+ "lineno": 290,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 290,
+ "start_region_line": 285
+ },
+ {
+ "end_outermost_loop": 291,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 291,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 291,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 297,
+ "end_region_line": 297,
+ "line": " def read_int16_t(self,addr):\n",
+ "lineno": 292,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 292,
+ "start_region_line": 292
+ },
+ {
+ "end_outermost_loop": 295,
+ "end_region_line": 297,
+ "line": " with self.pt_lock:\n",
+ "lineno": 293,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 293,
+ "start_region_line": 292
+ },
+ {
+ "end_outermost_loop": 295,
+ "end_region_line": 297,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 294,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 294,
+ "start_region_line": 292
+ },
+ {
+ "end_outermost_loop": 295,
+ "end_region_line": 297,
+ "line": " x, dxl_comm_result, dxl_error = self.packet_handler.read2ByteTxRx(self.port_handler, self.dxl_id, addr)\n",
+ "lineno": 295,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 26.092949237524003,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 295,
+ "start_region_line": 292
+ },
+ {
+ "end_outermost_loop": 296,
+ "end_region_line": 297,
+ "line": " xn = struct.unpack('h', arr.array('B',[DXL_LOBYTE(x), DXL_HIBYTE(x)]))[0]\n",
+ "lineno": 296,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 296,
+ "start_region_line": 292
+ },
+ {
+ "end_outermost_loop": 297,
+ "end_region_line": 297,
+ "line": " return xn, dxl_comm_result, dxl_error\n",
+ "lineno": 297,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 297,
+ "start_region_line": 292
+ },
+ {
+ "end_outermost_loop": 298,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 298,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 298,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 321,
+ "end_region_line": 321,
+ "line": " def do_ping(self,verbose=True):\n",
+ "lineno": 299,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 299,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 301,
+ "end_region_line": 321,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 300,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 300,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 301,
+ "end_region_line": 321,
+ "line": " return False\n",
+ "lineno": 301,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 301,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 302,
+ "end_region_line": 321,
+ "line": " try:\n",
+ "lineno": 302,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 302,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 305,
+ "end_region_line": 321,
+ "line": " with self.pt_lock:\n",
+ "lineno": 303,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 303,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 305,
+ "end_region_line": 321,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 304,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 304,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 305,
+ "end_region_line": 321,
+ "line": " dxl_model_number, dxl_comm_result, dxl_error = self.packet_handler.ping(self.port_handler, self.dxl_id)\n",
+ "lineno": 305,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 305,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 318,
+ "end_region_line": 321,
+ "line": " if self.handle_comm_result('XL430_PING', dxl_comm_result, dxl_error):\n",
+ "lineno": 306,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 306,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 307,
+ "end_region_line": 321,
+ "line": " self.dxl_model_name = MODEL_NUMBERS[dxl_model_number]\n",
+ "lineno": 307,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 307,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 308,
+ "end_region_line": 321,
+ "line": " self.logger.debug(\"[Dynamixel ID:%03d] ping Succeeded. Dynamixel model : %s. Baud %d\" % (\n",
+ "lineno": 308,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 308,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 309,
+ "end_region_line": 321,
+ "line": " self.dxl_id, self.dxl_model_name, self.baud))\n",
+ "lineno": 309,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 309,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 312,
+ "end_region_line": 321,
+ "line": " if verbose:\n",
+ "lineno": 310,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 310,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 311,
+ "end_region_line": 321,
+ "line": " print(\"[Dynamixel ID:%03d] ping Succeeded. Dynamixel model : %s. Baud %d\" % (\n",
+ "lineno": 311,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 311,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 312,
+ "end_region_line": 321,
+ "line": " self.dxl_id, self.dxl_model_name, self.baud))\n",
+ "lineno": 312,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 312,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 313,
+ "end_region_line": 321,
+ "line": " return True\n",
+ "lineno": 313,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 313,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 318,
+ "end_region_line": 321,
+ "line": " else:\n",
+ "lineno": 314,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 306,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 315,
+ "end_region_line": 321,
+ "line": " self.logger.debug(\"[Dynamixel ID:%03d] ping Failed.\" % (self.dxl_id))\n",
+ "lineno": 315,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 315,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 317,
+ "end_region_line": 321,
+ "line": " if verbose:\n",
+ "lineno": 316,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 316,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 317,
+ "end_region_line": 321,
+ "line": " print(\"[Dynamixel ID:%03d] ping Failed.\" % (self.dxl_id))\n",
+ "lineno": 317,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 317,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 318,
+ "end_region_line": 321,
+ "line": " return False\n",
+ "lineno": 318,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 318,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 319,
+ "end_region_line": 321,
+ "line": " except DynamixelCommError:\n",
+ "lineno": 319,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 319,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 320,
+ "end_region_line": 321,
+ "line": " self.logger.debug(\"[Dynamixel ID:%03d] Comm Error. Ping Failed.\" % (self.dxl_id))\n",
+ "lineno": 320,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 320,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 321,
+ "end_region_line": 321,
+ "line": " return False\n",
+ "lineno": 321,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 321,
+ "start_region_line": 299
+ },
+ {
+ "end_outermost_loop": 322,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 322,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 322,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 330,
+ "end_region_line": 330,
+ "line": " def get_id(self):\n",
+ "lineno": 323,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 323,
+ "start_region_line": 323
+ },
+ {
+ "end_outermost_loop": 325,
+ "end_region_line": 330,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 324,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 324,
+ "start_region_line": 323
+ },
+ {
+ "end_outermost_loop": 325,
+ "end_region_line": 330,
+ "line": " return 0\n",
+ "lineno": 325,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 325,
+ "start_region_line": 323
+ },
+ {
+ "end_outermost_loop": 328,
+ "end_region_line": 330,
+ "line": " with self.pt_lock:\n",
+ "lineno": 326,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 326,
+ "start_region_line": 323
+ },
+ {
+ "end_outermost_loop": 328,
+ "end_region_line": 330,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 327,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 327,
+ "start_region_line": 323
+ },
+ {
+ "end_outermost_loop": 328,
+ "end_region_line": 330,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_ID)\n",
+ "lineno": 328,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 328,
+ "start_region_line": 323
+ },
+ {
+ "end_outermost_loop": 329,
+ "end_region_line": 330,
+ "line": " self.handle_comm_result('XL430_ADDR_ID', dxl_comm_result, dxl_error)\n",
+ "lineno": 329,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 329,
+ "start_region_line": 323
+ },
+ {
+ "end_outermost_loop": 330,
+ "end_region_line": 330,
+ "line": " return p\n",
+ "lineno": 330,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 330,
+ "start_region_line": 323
+ },
+ {
+ "end_outermost_loop": 331,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 331,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 331,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 338,
+ "end_region_line": 338,
+ "line": " def set_id(self,id):\n",
+ "lineno": 332,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 332,
+ "start_region_line": 332
+ },
+ {
+ "end_outermost_loop": 334,
+ "end_region_line": 338,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 333,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 333,
+ "start_region_line": 332
+ },
+ {
+ "end_outermost_loop": 334,
+ "end_region_line": 338,
+ "line": " return\n",
+ "lineno": 334,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 334,
+ "start_region_line": 332
+ },
+ {
+ "end_outermost_loop": 337,
+ "end_region_line": 338,
+ "line": " with self.pt_lock:\n",
+ "lineno": 335,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 335,
+ "start_region_line": 332
+ },
+ {
+ "end_outermost_loop": 337,
+ "end_region_line": 338,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 336,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 336,
+ "start_region_line": 332
+ },
+ {
+ "end_outermost_loop": 337,
+ "end_region_line": 338,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_ID, int(id))\n",
+ "lineno": 337,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 337,
+ "start_region_line": 332
+ },
+ {
+ "end_outermost_loop": 338,
+ "end_region_line": 338,
+ "line": " self.handle_comm_result('XL430_ADDR_ID', dxl_comm_result, dxl_error)\n",
+ "lineno": 338,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 338,
+ "start_region_line": 332
+ },
+ {
+ "end_outermost_loop": 339,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 339,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 339,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 355,
+ "end_region_line": 355,
+ "line": " def get_baud_rate(self):\n",
+ "lineno": 340,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 340,
+ "start_region_line": 340
+ },
+ {
+ "end_outermost_loop": 341,
+ "end_region_line": 355,
+ "line": " \"\"\"Retrieves the baud rate of Dynamixel communication.\n",
+ "lineno": 341,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 341,
+ "start_region_line": 340
+ },
+ {
+ "end_outermost_loop": 342,
+ "end_region_line": 355,
+ "line": "\n",
+ "lineno": 342,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 342,
+ "start_region_line": 340
+ },
+ {
+ "end_outermost_loop": 343,
+ "end_region_line": 355,
+ "line": " Returns\n",
+ "lineno": 343,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 343,
+ "start_region_line": 340
+ },
+ {
+ "end_outermost_loop": 344,
+ "end_region_line": 355,
+ "line": " -------\n",
+ "lineno": 344,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 344,
+ "start_region_line": 340
+ },
+ {
+ "end_outermost_loop": 345,
+ "end_region_line": 355,
+ "line": " int\n",
+ "lineno": 345,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 345,
+ "start_region_line": 340
+ },
+ {
+ "end_outermost_loop": 346,
+ "end_region_line": 355,
+ "line": " baud rate from `BAUD_MAP` if successful communication, else -1\n",
+ "lineno": 346,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 346,
+ "start_region_line": 340
+ },
+ {
+ "end_outermost_loop": 347,
+ "end_region_line": 355,
+ "line": " \"\"\"\n",
+ "lineno": 347,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 347,
+ "start_region_line": 340
+ },
+ {
+ "end_outermost_loop": 349,
+ "end_region_line": 355,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 348,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 348,
+ "start_region_line": 340
+ },
+ {
+ "end_outermost_loop": 349,
+ "end_region_line": 355,
+ "line": " return -1\n",
+ "lineno": 349,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 349,
+ "start_region_line": 340
+ },
+ {
+ "end_outermost_loop": 352,
+ "end_region_line": 355,
+ "line": " with self.pt_lock:\n",
+ "lineno": 350,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 350,
+ "start_region_line": 340
+ },
+ {
+ "end_outermost_loop": 352,
+ "end_region_line": 355,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 351,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 351,
+ "start_region_line": 340
+ },
+ {
+ "end_outermost_loop": 352,
+ "end_region_line": 355,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_BAUD_RATE)\n",
+ "lineno": 352,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 352,
+ "start_region_line": 340
+ },
+ {
+ "end_outermost_loop": 354,
+ "end_region_line": 355,
+ "line": " if not self.handle_comm_result('XL430_ADDR_BAUD_RATE', dxl_comm_result, dxl_error):\n",
+ "lineno": 353,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 353,
+ "start_region_line": 340
+ },
+ {
+ "end_outermost_loop": 354,
+ "end_region_line": 355,
+ "line": " return -1\n",
+ "lineno": 354,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 354,
+ "start_region_line": 340
+ },
+ {
+ "end_outermost_loop": 355,
+ "end_region_line": 355,
+ "line": " return list(BAUD_MAP.keys())[list(BAUD_MAP.values()).index(p)]\n",
+ "lineno": 355,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 355,
+ "start_region_line": 340
+ },
+ {
+ "end_outermost_loop": 356,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 356,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 356,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 380,
+ "end_region_line": 380,
+ "line": " def set_baud_rate(self, rate):\n",
+ "lineno": 357,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 357,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 358,
+ "end_region_line": 380,
+ "line": " \"\"\"Sets the baud rate of Dynamixel communication.\n",
+ "lineno": 358,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 358,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 359,
+ "end_region_line": 380,
+ "line": "\n",
+ "lineno": 359,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 359,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 360,
+ "end_region_line": 380,
+ "line": " Parameters\n",
+ "lineno": 360,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 360,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 361,
+ "end_region_line": 380,
+ "line": " ----------\n",
+ "lineno": 361,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 361,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 362,
+ "end_region_line": 380,
+ "line": " rate : int\n",
+ "lineno": 362,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 362,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 363,
+ "end_region_line": 380,
+ "line": " baud rate option from `BAUD_MAP`\n",
+ "lineno": 363,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 363,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 364,
+ "end_region_line": 380,
+ "line": "\n",
+ "lineno": 364,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 364,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 365,
+ "end_region_line": 380,
+ "line": " Returns\n",
+ "lineno": 365,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 365,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 366,
+ "end_region_line": 380,
+ "line": " -------\n",
+ "lineno": 366,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 366,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 367,
+ "end_region_line": 380,
+ "line": " bool\n",
+ "lineno": 367,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 367,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 368,
+ "end_region_line": 380,
+ "line": " True if the baud rate was set successfully, else False\n",
+ "lineno": 368,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 368,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 369,
+ "end_region_line": 380,
+ "line": " \"\"\"\n",
+ "lineno": 369,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 369,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 371,
+ "end_region_line": 380,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 370,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 370,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 371,
+ "end_region_line": 380,
+ "line": " return -1\n",
+ "lineno": 371,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 371,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 374,
+ "end_region_line": 380,
+ "line": " if rate not in BAUD_MAP:\n",
+ "lineno": 372,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 372,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 373,
+ "end_region_line": 380,
+ "line": " self.logger.debug(\"Invalid baud rate\")\n",
+ "lineno": 373,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 373,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 374,
+ "end_region_line": 380,
+ "line": " return False\n",
+ "lineno": 374,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 374,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 375,
+ "end_region_line": 380,
+ "line": "\n",
+ "lineno": 375,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 375,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 376,
+ "end_region_line": 380,
+ "line": " self.disable_torque()\n",
+ "lineno": 376,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 376,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 379,
+ "end_region_line": 380,
+ "line": " with self.pt_lock:\n",
+ "lineno": 377,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 377,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 379,
+ "end_region_line": 380,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 378,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 378,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 379,
+ "end_region_line": 380,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_BAUD_RATE, BAUD_MAP[rate])\n",
+ "lineno": 379,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 379,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 380,
+ "end_region_line": 380,
+ "line": " return self.handle_comm_result('XL430_ADDR_BAUD_RATE', dxl_comm_result, dxl_error)\n",
+ "lineno": 380,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 380,
+ "start_region_line": 357
+ },
+ {
+ "end_outermost_loop": 381,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 381,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 381,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 1035,
+ "end_region_line": 1035,
+ "line": " #Hello Robot Specific\n",
+ "lineno": 382,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 137,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 390,
+ "end_region_line": 390,
+ "line": " def is_calibrated(self):\n",
+ "lineno": 383,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 383,
+ "start_region_line": 383
+ },
+ {
+ "end_outermost_loop": 385,
+ "end_region_line": 390,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 384,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 384,
+ "start_region_line": 383
+ },
+ {
+ "end_outermost_loop": 385,
+ "end_region_line": 390,
+ "line": " return False\n",
+ "lineno": 385,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 385,
+ "start_region_line": 383
+ },
+ {
+ "end_outermost_loop": 388,
+ "end_region_line": 390,
+ "line": " with self.pt_lock:\n",
+ "lineno": 386,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 386,
+ "start_region_line": 383
+ },
+ {
+ "end_outermost_loop": 388,
+ "end_region_line": 390,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 387,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 387,
+ "start_region_line": 383
+ },
+ {
+ "end_outermost_loop": 388,
+ "end_region_line": 390,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_HELLO_CALIBRATED)\n",
+ "lineno": 388,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 388,
+ "start_region_line": 383
+ },
+ {
+ "end_outermost_loop": 389,
+ "end_region_line": 390,
+ "line": " self.handle_comm_result('XL430_ADDR_HELLO_CALIBRATED', dxl_comm_result, dxl_error)\n",
+ "lineno": 389,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 389,
+ "start_region_line": 383
+ },
+ {
+ "end_outermost_loop": 390,
+ "end_region_line": 390,
+ "line": " return p\n",
+ "lineno": 390,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 390,
+ "start_region_line": 383
+ },
+ {
+ "end_outermost_loop": 391,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 391,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 391,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 1035,
+ "end_region_line": 1035,
+ "line": " # Hello Robot Specific\n",
+ "lineno": 392,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 137,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 399,
+ "end_region_line": 399,
+ "line": " def set_calibrated(self,x):\n",
+ "lineno": 393,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 393,
+ "start_region_line": 393
+ },
+ {
+ "end_outermost_loop": 395,
+ "end_region_line": 399,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 394,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 394,
+ "start_region_line": 393
+ },
+ {
+ "end_outermost_loop": 395,
+ "end_region_line": 399,
+ "line": " return\n",
+ "lineno": 395,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 395,
+ "start_region_line": 393
+ },
+ {
+ "end_outermost_loop": 398,
+ "end_region_line": 399,
+ "line": " with self.pt_lock:\n",
+ "lineno": 396,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 396,
+ "start_region_line": 393
+ },
+ {
+ "end_outermost_loop": 398,
+ "end_region_line": 399,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 397,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 397,
+ "start_region_line": 393
+ },
+ {
+ "end_outermost_loop": 398,
+ "end_region_line": 399,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_HELLO_CALIBRATED, int(x!=0))\n",
+ "lineno": 398,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 398,
+ "start_region_line": 393
+ },
+ {
+ "end_outermost_loop": 399,
+ "end_region_line": 399,
+ "line": " self.handle_comm_result('XL430_ADDR_HELLO_CALIBRATED', dxl_comm_result, dxl_error)\n",
+ "lineno": 399,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 399,
+ "start_region_line": 393
+ },
+ {
+ "end_outermost_loop": 400,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 400,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 400,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 412,
+ "end_region_line": 412,
+ "line": " def do_reboot(self):\n",
+ "lineno": 401,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 401,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 403,
+ "end_region_line": 412,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 402,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 402,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 403,
+ "end_region_line": 412,
+ "line": " return False\n",
+ "lineno": 403,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 403,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 406,
+ "end_region_line": 412,
+ "line": " with self.pt_lock:\n",
+ "lineno": 404,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 404,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 406,
+ "end_region_line": 412,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 405,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 405,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 406,
+ "end_region_line": 412,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.reboot(self.port_handler, self.dxl_id)\n",
+ "lineno": 406,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 406,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 412,
+ "end_region_line": 412,
+ "line": " if self.handle_comm_result('XL430_REBOOT', dxl_comm_result, dxl_error):\n",
+ "lineno": 407,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 407,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 408,
+ "end_region_line": 412,
+ "line": " print(\"[Dynamixel ID:%03d] Reboot Succeeded.\" % (self.dxl_id))\n",
+ "lineno": 408,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 408,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 409,
+ "end_region_line": 412,
+ "line": " return True\n",
+ "lineno": 409,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 409,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 412,
+ "end_region_line": 412,
+ "line": " else:\n",
+ "lineno": 410,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 407,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 411,
+ "end_region_line": 412,
+ "line": " print(\"[Dynamixel ID:%03d] Reboot Failed.\" % (self.dxl_id))\n",
+ "lineno": 411,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 411,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 412,
+ "end_region_line": 412,
+ "line": " return False\n",
+ "lineno": 412,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 412,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 413,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 413,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 413,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 421,
+ "end_region_line": 421,
+ "line": " def get_shutdown(self):\n",
+ "lineno": 414,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 414,
+ "start_region_line": 414
+ },
+ {
+ "end_outermost_loop": 416,
+ "end_region_line": 421,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 415,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 415,
+ "start_region_line": 414
+ },
+ {
+ "end_outermost_loop": 416,
+ "end_region_line": 421,
+ "line": " return 0\n",
+ "lineno": 416,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 416,
+ "start_region_line": 414
+ },
+ {
+ "end_outermost_loop": 419,
+ "end_region_line": 421,
+ "line": " with self.pt_lock:\n",
+ "lineno": 417,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 417,
+ "start_region_line": 414
+ },
+ {
+ "end_outermost_loop": 419,
+ "end_region_line": 421,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 418,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 418,
+ "start_region_line": 414
+ },
+ {
+ "end_outermost_loop": 419,
+ "end_region_line": 421,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_SHUTDOWN)\n",
+ "lineno": 419,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 419,
+ "start_region_line": 414
+ },
+ {
+ "end_outermost_loop": 420,
+ "end_region_line": 421,
+ "line": " self.handle_comm_result('XL430_ADDR_SHUTDOWN', dxl_comm_result, dxl_error)\n",
+ "lineno": 420,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 420,
+ "start_region_line": 414
+ },
+ {
+ "end_outermost_loop": 421,
+ "end_region_line": 421,
+ "line": " return p\n",
+ "lineno": 421,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 421,
+ "start_region_line": 414
+ },
+ {
+ "end_outermost_loop": 422,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 422,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 422,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 429,
+ "end_region_line": 429,
+ "line": " def set_shutdown(self):\n",
+ "lineno": 423,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 423,
+ "start_region_line": 423
+ },
+ {
+ "end_outermost_loop": 425,
+ "end_region_line": 429,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 424,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 424,
+ "start_region_line": 423
+ },
+ {
+ "end_outermost_loop": 425,
+ "end_region_line": 429,
+ "line": " return\n",
+ "lineno": 425,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 425,
+ "start_region_line": 423
+ },
+ {
+ "end_outermost_loop": 428,
+ "end_region_line": 429,
+ "line": " with self.pt_lock:\n",
+ "lineno": 426,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 426,
+ "start_region_line": 423
+ },
+ {
+ "end_outermost_loop": 428,
+ "end_region_line": 429,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 427,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 427,
+ "start_region_line": 423
+ },
+ {
+ "end_outermost_loop": 428,
+ "end_region_line": 429,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_SHUTDOWN, id)\n",
+ "lineno": 428,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 428,
+ "start_region_line": 423
+ },
+ {
+ "end_outermost_loop": 429,
+ "end_region_line": 429,
+ "line": " self.handle_comm_result('XL430_ADDR_SHUTDOWN', dxl_comm_result, dxl_error)\n",
+ "lineno": 429,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 429,
+ "start_region_line": 423
+ },
+ {
+ "end_outermost_loop": 430,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 430,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 430,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 439,
+ "end_region_line": 439,
+ "line": " def get_hardware_error(self):\n",
+ "lineno": 431,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 431,
+ "start_region_line": 431
+ },
+ {
+ "end_outermost_loop": 433,
+ "end_region_line": 439,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 432,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 432,
+ "start_region_line": 431
+ },
+ {
+ "end_outermost_loop": 433,
+ "end_region_line": 439,
+ "line": " return 0\n",
+ "lineno": 433,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 433,
+ "start_region_line": 431
+ },
+ {
+ "end_outermost_loop": 437,
+ "end_region_line": 439,
+ "line": " with self.pt_lock:\n",
+ "lineno": 434,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 434,
+ "start_region_line": 431
+ },
+ {
+ "end_outermost_loop": 437,
+ "end_region_line": 439,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 435,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 435,
+ "start_region_line": 431
+ },
+ {
+ "end_outermost_loop": 436,
+ "end_region_line": 439,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read1ByteTxRx(self.port_handler, self.dxl_id,\n",
+ "lineno": 436,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 436,
+ "start_region_line": 431
+ },
+ {
+ "end_outermost_loop": 437,
+ "end_region_line": 439,
+ "line": " XL430_ADDR_HARDWARE_ERROR_STATUS)\n",
+ "lineno": 437,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 437,
+ "start_region_line": 431
+ },
+ {
+ "end_outermost_loop": 438,
+ "end_region_line": 439,
+ "line": " self.handle_comm_result('XL430_ADDR_HARDWARE_ERROR_STATUS', dxl_comm_result, dxl_error)\n",
+ "lineno": 438,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 438,
+ "start_region_line": 431
+ },
+ {
+ "end_outermost_loop": 439,
+ "end_region_line": 439,
+ "line": " return p\n",
+ "lineno": 439,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 439,
+ "start_region_line": 431
+ },
+ {
+ "end_outermost_loop": 440,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 440,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 440,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 441,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 441,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 441,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 448,
+ "end_region_line": 448,
+ "line": " def enable_torque(self):\n",
+ "lineno": 442,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 442,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 444,
+ "end_region_line": 448,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 443,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 443,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 444,
+ "end_region_line": 448,
+ "line": " return\n",
+ "lineno": 444,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 444,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 447,
+ "end_region_line": 448,
+ "line": " with self.pt_lock:\n",
+ "lineno": 445,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 445,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 447,
+ "end_region_line": 448,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 446,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 446,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 447,
+ "end_region_line": 448,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_TORQUE_ENABLE, 1)\n",
+ "lineno": 447,
+ "memory_samples": [
+ [
+ 1779390877,
+ 50.50844478607178
+ ]
+ ],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 45.243716051609546,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 10.002431869506836,
+ "n_malloc_mb": 10.002431869506836,
+ "n_mallocs": 0,
+ "n_peak_mb": 10.002431869506836,
+ "n_python_fraction": 0.962637,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.19989979385085394,
+ "start_outermost_loop": 447,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 448,
+ "end_region_line": 448,
+ "line": " self.handle_comm_result('XL430_ADDR_TORQUE_ENABLE', dxl_comm_result, dxl_error)\n",
+ "lineno": 448,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 448,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 449,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 449,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 449,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 450,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 450,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 450,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 457,
+ "end_region_line": 457,
+ "line": " def disable_torque(self):\n",
+ "lineno": 451,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 451,
+ "start_region_line": 451
+ },
+ {
+ "end_outermost_loop": 453,
+ "end_region_line": 457,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 452,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 452,
+ "start_region_line": 451
+ },
+ {
+ "end_outermost_loop": 453,
+ "end_region_line": 457,
+ "line": " return\n",
+ "lineno": 453,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 453,
+ "start_region_line": 451
+ },
+ {
+ "end_outermost_loop": 456,
+ "end_region_line": 457,
+ "line": " with self.pt_lock:\n",
+ "lineno": 454,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 454,
+ "start_region_line": 451
+ },
+ {
+ "end_outermost_loop": 456,
+ "end_region_line": 457,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 455,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 455,
+ "start_region_line": 451
+ },
+ {
+ "end_outermost_loop": 456,
+ "end_region_line": 457,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_TORQUE_ENABLE, 0)\n",
+ "lineno": 456,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 40.3356627451006,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 456,
+ "start_region_line": 451
+ },
+ {
+ "end_outermost_loop": 457,
+ "end_region_line": 457,
+ "line": " self.handle_comm_result('XL430_ADDR_TORQUE_ENABLE', dxl_comm_result, dxl_error)\n",
+ "lineno": 457,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 457,
+ "start_region_line": 451
+ },
+ {
+ "end_outermost_loop": 458,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 458,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 458,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 465,
+ "end_region_line": 465,
+ "line": " def set_return_delay_time(self,x):\n",
+ "lineno": 459,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 459,
+ "start_region_line": 459
+ },
+ {
+ "end_outermost_loop": 461,
+ "end_region_line": 465,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 460,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 460,
+ "start_region_line": 459
+ },
+ {
+ "end_outermost_loop": 461,
+ "end_region_line": 465,
+ "line": " return\n",
+ "lineno": 461,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 461,
+ "start_region_line": 459
+ },
+ {
+ "end_outermost_loop": 464,
+ "end_region_line": 465,
+ "line": " with self.pt_lock:\n",
+ "lineno": 462,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 462,
+ "start_region_line": 459
+ },
+ {
+ "end_outermost_loop": 464,
+ "end_region_line": 465,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 463,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 463,
+ "start_region_line": 459
+ },
+ {
+ "end_outermost_loop": 464,
+ "end_region_line": 465,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id,XL430_ADDR_RETURN_DELAY_TIME, int(x))\n",
+ "lineno": 464,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 464,
+ "start_region_line": 459
+ },
+ {
+ "end_outermost_loop": 465,
+ "end_region_line": 465,
+ "line": " self.handle_comm_result('XL430_ADDR_RETURN_DELAY_TIME', dxl_comm_result, dxl_error)\n",
+ "lineno": 465,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 465,
+ "start_region_line": 459
+ },
+ {
+ "end_outermost_loop": 466,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 466,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 466,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 475,
+ "end_region_line": 475,
+ "line": " def get_return_delay_time(self):\n",
+ "lineno": 467,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 467,
+ "start_region_line": 467
+ },
+ {
+ "end_outermost_loop": 469,
+ "end_region_line": 475,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 468,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 468,
+ "start_region_line": 467
+ },
+ {
+ "end_outermost_loop": 469,
+ "end_region_line": 475,
+ "line": " return 0\n",
+ "lineno": 469,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 469,
+ "start_region_line": 467
+ },
+ {
+ "end_outermost_loop": 473,
+ "end_region_line": 475,
+ "line": " with self.pt_lock:\n",
+ "lineno": 470,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 470,
+ "start_region_line": 467
+ },
+ {
+ "end_outermost_loop": 473,
+ "end_region_line": 475,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 471,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 471,
+ "start_region_line": 467
+ },
+ {
+ "end_outermost_loop": 472,
+ "end_region_line": 475,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read1ByteTxRx(self.port_handler, self.dxl_id,\n",
+ "lineno": 472,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 472,
+ "start_region_line": 467
+ },
+ {
+ "end_outermost_loop": 473,
+ "end_region_line": 475,
+ "line": " XL430_ADDR_RETURN_DELAY_TIME)\n",
+ "lineno": 473,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 473,
+ "start_region_line": 467
+ },
+ {
+ "end_outermost_loop": 474,
+ "end_region_line": 475,
+ "line": " self.handle_comm_result('XL430_ADDR_HARDWARE_ERROR_STATUS', dxl_comm_result, dxl_error)\n",
+ "lineno": 474,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 474,
+ "start_region_line": 467
+ },
+ {
+ "end_outermost_loop": 475,
+ "end_region_line": 475,
+ "line": " return p\n",
+ "lineno": 475,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 475,
+ "start_region_line": 467
+ },
+ {
+ "end_outermost_loop": 476,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 476,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 476,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 483,
+ "end_region_line": 483,
+ "line": " def set_pwm(self,x):\n",
+ "lineno": 477,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 477,
+ "start_region_line": 477
+ },
+ {
+ "end_outermost_loop": 479,
+ "end_region_line": 483,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 478,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 478,
+ "start_region_line": 477
+ },
+ {
+ "end_outermost_loop": 479,
+ "end_region_line": 483,
+ "line": " return\n",
+ "lineno": 479,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 479,
+ "start_region_line": 477
+ },
+ {
+ "end_outermost_loop": 482,
+ "end_region_line": 483,
+ "line": " with self.pt_lock:\n",
+ "lineno": 480,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 480,
+ "start_region_line": 477
+ },
+ {
+ "end_outermost_loop": 482,
+ "end_region_line": 483,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 481,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 481,
+ "start_region_line": 477
+ },
+ {
+ "end_outermost_loop": 482,
+ "end_region_line": 483,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write2ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_GOAL_PWM, int(x))\n",
+ "lineno": 482,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 482,
+ "start_region_line": 477
+ },
+ {
+ "end_outermost_loop": 483,
+ "end_region_line": 483,
+ "line": " self.handle_comm_result('XL430_ADDR_GOAL_PWM', dxl_comm_result, dxl_error)\n",
+ "lineno": 483,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 483,
+ "start_region_line": 477
+ },
+ {
+ "end_outermost_loop": 484,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 484,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 484,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 489,
+ "end_region_line": 489,
+ "line": " def set_current_limit(self,i):\n",
+ "lineno": 485,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 485,
+ "start_region_line": 485
+ },
+ {
+ "end_outermost_loop": 488,
+ "end_region_line": 489,
+ "line": " with self.pt_lock:\n",
+ "lineno": 486,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 486,
+ "start_region_line": 485
+ },
+ {
+ "end_outermost_loop": 488,
+ "end_region_line": 489,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 487,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 487,
+ "start_region_line": 485
+ },
+ {
+ "end_outermost_loop": 488,
+ "end_region_line": 489,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write2ByteTxRx(self.port_handler, self.dxl_id, XM430_ADDR_CURRENT_LIMIT, int(i))\n",
+ "lineno": 488,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 488,
+ "start_region_line": 485
+ },
+ {
+ "end_outermost_loop": 489,
+ "end_region_line": 489,
+ "line": " self.handle_comm_result('XM430_ADDR_CURRENT_LIMIT', dxl_comm_result, dxl_error)\n",
+ "lineno": 489,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 489,
+ "start_region_line": 485
+ },
+ {
+ "end_outermost_loop": 490,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 490,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 490,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 499,
+ "end_region_line": 499,
+ "line": " def get_current_limit(self):\n",
+ "lineno": 491,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 491,
+ "start_region_line": 491
+ },
+ {
+ "end_outermost_loop": 493,
+ "end_region_line": 499,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 492,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 492,
+ "start_region_line": 491
+ },
+ {
+ "end_outermost_loop": 493,
+ "end_region_line": 499,
+ "line": " return 0\n",
+ "lineno": 493,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 493,
+ "start_region_line": 491
+ },
+ {
+ "end_outermost_loop": 497,
+ "end_region_line": 499,
+ "line": " with self.pt_lock:\n",
+ "lineno": 494,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 494,
+ "start_region_line": 491
+ },
+ {
+ "end_outermost_loop": 497,
+ "end_region_line": 499,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 495,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 495,
+ "start_region_line": 491
+ },
+ {
+ "end_outermost_loop": 496,
+ "end_region_line": 499,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read2ByteTxRx(self.port_handler, self.dxl_id,\n",
+ "lineno": 496,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 496,
+ "start_region_line": 491
+ },
+ {
+ "end_outermost_loop": 497,
+ "end_region_line": 499,
+ "line": " XM430_ADDR_CURRENT_LIMIT)\n",
+ "lineno": 497,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 497,
+ "start_region_line": 491
+ },
+ {
+ "end_outermost_loop": 498,
+ "end_region_line": 499,
+ "line": " self.handle_comm_result('XM430_ADDR_CURRENT_LIMIT', dxl_comm_result, dxl_error)\n",
+ "lineno": 498,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 498,
+ "start_region_line": 491
+ },
+ {
+ "end_outermost_loop": 499,
+ "end_region_line": 499,
+ "line": " return p\n",
+ "lineno": 499,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 499,
+ "start_region_line": 491
+ },
+ {
+ "end_outermost_loop": 500,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 500,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 500,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 507,
+ "end_region_line": 507,
+ "line": " def enable_multiturn(self):\n",
+ "lineno": 501,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 501,
+ "start_region_line": 501
+ },
+ {
+ "end_outermost_loop": 503,
+ "end_region_line": 507,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 502,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 502,
+ "start_region_line": 501
+ },
+ {
+ "end_outermost_loop": 503,
+ "end_region_line": 507,
+ "line": " return\n",
+ "lineno": 503,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 503,
+ "start_region_line": 501
+ },
+ {
+ "end_outermost_loop": 506,
+ "end_region_line": 507,
+ "line": " with self.pt_lock:\n",
+ "lineno": 504,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 504,
+ "start_region_line": 501
+ },
+ {
+ "end_outermost_loop": 506,
+ "end_region_line": 507,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 505,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 505,
+ "start_region_line": 501
+ },
+ {
+ "end_outermost_loop": 506,
+ "end_region_line": 507,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_OPERATING_MODE, 4)\n",
+ "lineno": 506,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 506,
+ "start_region_line": 501
+ },
+ {
+ "end_outermost_loop": 507,
+ "end_region_line": 507,
+ "line": " self.handle_comm_result('XL430_ADDR_OPERATING_MODE', dxl_comm_result, dxl_error)\n",
+ "lineno": 507,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 507,
+ "start_region_line": 501
+ },
+ {
+ "end_outermost_loop": 508,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 508,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 508,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 515,
+ "end_region_line": 515,
+ "line": " def enable_pwm(self):\n",
+ "lineno": 509,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 509,
+ "start_region_line": 509
+ },
+ {
+ "end_outermost_loop": 511,
+ "end_region_line": 515,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 510,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 510,
+ "start_region_line": 509
+ },
+ {
+ "end_outermost_loop": 511,
+ "end_region_line": 515,
+ "line": " return\n",
+ "lineno": 511,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 511,
+ "start_region_line": 509
+ },
+ {
+ "end_outermost_loop": 514,
+ "end_region_line": 515,
+ "line": " with self.pt_lock:\n",
+ "lineno": 512,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 512,
+ "start_region_line": 509
+ },
+ {
+ "end_outermost_loop": 514,
+ "end_region_line": 515,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 513,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 513,
+ "start_region_line": 509
+ },
+ {
+ "end_outermost_loop": 514,
+ "end_region_line": 515,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_OPERATING_MODE, 16)\n",
+ "lineno": 514,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 514,
+ "start_region_line": 509
+ },
+ {
+ "end_outermost_loop": 515,
+ "end_region_line": 515,
+ "line": " self.handle_comm_result('XL430_ADDR_OPERATING_MODE', dxl_comm_result, dxl_error)\n",
+ "lineno": 515,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 515,
+ "start_region_line": 509
+ },
+ {
+ "end_outermost_loop": 516,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 516,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 516,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 523,
+ "end_region_line": 523,
+ "line": " def enable_pos(self):\n",
+ "lineno": 517,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 517,
+ "start_region_line": 517
+ },
+ {
+ "end_outermost_loop": 519,
+ "end_region_line": 523,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 518,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 518,
+ "start_region_line": 517
+ },
+ {
+ "end_outermost_loop": 519,
+ "end_region_line": 523,
+ "line": " return\n",
+ "lineno": 519,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 519,
+ "start_region_line": 517
+ },
+ {
+ "end_outermost_loop": 522,
+ "end_region_line": 523,
+ "line": " with self.pt_lock:\n",
+ "lineno": 520,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 520,
+ "start_region_line": 517
+ },
+ {
+ "end_outermost_loop": 522,
+ "end_region_line": 523,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 521,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 521,
+ "start_region_line": 517
+ },
+ {
+ "end_outermost_loop": 522,
+ "end_region_line": 523,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_OPERATING_MODE, 3)\n",
+ "lineno": 522,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 27.619792161021117,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 522,
+ "start_region_line": 517
+ },
+ {
+ "end_outermost_loop": 523,
+ "end_region_line": 523,
+ "line": " self.handle_comm_result('XL430_ADDR_OPERATING_MODE', dxl_comm_result, dxl_error)\n",
+ "lineno": 523,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 523,
+ "start_region_line": 517
+ },
+ {
+ "end_outermost_loop": 524,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 524,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 524,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 531,
+ "end_region_line": 531,
+ "line": " def enable_vel(self):\n",
+ "lineno": 525,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 525,
+ "start_region_line": 525
+ },
+ {
+ "end_outermost_loop": 527,
+ "end_region_line": 531,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 526,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 526,
+ "start_region_line": 525
+ },
+ {
+ "end_outermost_loop": 527,
+ "end_region_line": 531,
+ "line": " return\n",
+ "lineno": 527,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 527,
+ "start_region_line": 525
+ },
+ {
+ "end_outermost_loop": 530,
+ "end_region_line": 531,
+ "line": " with self.pt_lock:\n",
+ "lineno": 528,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 528,
+ "start_region_line": 525
+ },
+ {
+ "end_outermost_loop": 530,
+ "end_region_line": 531,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 529,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 529,
+ "start_region_line": 525
+ },
+ {
+ "end_outermost_loop": 530,
+ "end_region_line": 531,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_OPERATING_MODE, 1)\n",
+ "lineno": 530,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 530,
+ "start_region_line": 525
+ },
+ {
+ "end_outermost_loop": 531,
+ "end_region_line": 531,
+ "line": " self.handle_comm_result('XL430_ADDR_OPERATING_MODE', dxl_comm_result, dxl_error)\n",
+ "lineno": 531,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 531,
+ "start_region_line": 525
+ },
+ {
+ "end_outermost_loop": 532,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 532,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 532,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 1035,
+ "end_region_line": 1035,
+ "line": " # XM Series\n",
+ "lineno": 533,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 137,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 1035,
+ "end_region_line": 1035,
+ "line": " # https://forum.robotis.com/t/how-does-current-mode-work-in-xm430-w210/203\n",
+ "lineno": 534,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 137,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 535,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 535,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 535,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 540,
+ "end_region_line": 540,
+ "line": " def enable_pos_current(self):\n",
+ "lineno": 536,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 536,
+ "start_region_line": 536
+ },
+ {
+ "end_outermost_loop": 539,
+ "end_region_line": 540,
+ "line": " with self.pt_lock:\n",
+ "lineno": 537,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 537,
+ "start_region_line": 536
+ },
+ {
+ "end_outermost_loop": 539,
+ "end_region_line": 540,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 538,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 538,
+ "start_region_line": 536
+ },
+ {
+ "end_outermost_loop": 539,
+ "end_region_line": 540,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_OPERATING_MODE, 5)\n",
+ "lineno": 539,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 539,
+ "start_region_line": 536
+ },
+ {
+ "end_outermost_loop": 540,
+ "end_region_line": 540,
+ "line": " self.handle_comm_result('XL430_ADDR_OPERATING_MODE', dxl_comm_result, dxl_error)\n",
+ "lineno": 540,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 540,
+ "start_region_line": 536
+ },
+ {
+ "end_outermost_loop": 1035,
+ "end_region_line": 1035,
+ "line": " #XM Series\n",
+ "lineno": 541,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 137,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 546,
+ "end_region_line": 546,
+ "line": " def enable_current(self):\n",
+ "lineno": 542,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 542,
+ "start_region_line": 542
+ },
+ {
+ "end_outermost_loop": 545,
+ "end_region_line": 546,
+ "line": " with self.pt_lock:\n",
+ "lineno": 543,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 543,
+ "start_region_line": 542
+ },
+ {
+ "end_outermost_loop": 545,
+ "end_region_line": 546,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 544,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 544,
+ "start_region_line": 542
+ },
+ {
+ "end_outermost_loop": 545,
+ "end_region_line": 546,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_OPERATING_MODE, 0)\n",
+ "lineno": 545,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 545,
+ "start_region_line": 542
+ },
+ {
+ "end_outermost_loop": 546,
+ "end_region_line": 546,
+ "line": " self.handle_comm_result('XL430_ADDR_OPERATING_MODE', dxl_comm_result, dxl_error)\n",
+ "lineno": 546,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 546,
+ "start_region_line": 542
+ },
+ {
+ "end_outermost_loop": 547,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 547,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 547,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 548,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 548,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 548,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 560,
+ "end_region_line": 560,
+ "line": " def get_operating_mode(self):\n",
+ "lineno": 549,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 549,
+ "start_region_line": 549
+ },
+ {
+ "end_outermost_loop": 551,
+ "end_region_line": 560,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 550,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 550,
+ "start_region_line": 549
+ },
+ {
+ "end_outermost_loop": 551,
+ "end_region_line": 560,
+ "line": " return 0\n",
+ "lineno": 551,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 551,
+ "start_region_line": 549
+ },
+ {
+ "end_outermost_loop": 552,
+ "end_region_line": 560,
+ "line": " try:\n",
+ "lineno": 552,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 552,
+ "start_region_line": 549
+ },
+ {
+ "end_outermost_loop": 553,
+ "end_region_line": 560,
+ "line": " # Catching DynamixelCommError exception to gracefully handle overload errors without erroring out the main script\n",
+ "lineno": 553,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 553,
+ "start_region_line": 549
+ },
+ {
+ "end_outermost_loop": 556,
+ "end_region_line": 560,
+ "line": " with self.pt_lock:\n",
+ "lineno": 554,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 554,
+ "start_region_line": 549
+ },
+ {
+ "end_outermost_loop": 556,
+ "end_region_line": 560,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 555,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 555,
+ "start_region_line": 549
+ },
+ {
+ "end_outermost_loop": 556,
+ "end_region_line": 560,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read1ByteTxRx(self.port_handler, self.dxl_id,XL430_ADDR_OPERATING_MODE)\n",
+ "lineno": 556,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 556,
+ "start_region_line": 549
+ },
+ {
+ "end_outermost_loop": 557,
+ "end_region_line": 560,
+ "line": " self.handle_comm_result('XL430_ADDR_OPERATING_MODE', dxl_comm_result, dxl_error)\n",
+ "lineno": 557,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 557,
+ "start_region_line": 549
+ },
+ {
+ "end_outermost_loop": 558,
+ "end_region_line": 560,
+ "line": " except Exception as DynamixelCommError:\n",
+ "lineno": 558,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 558,
+ "start_region_line": 549
+ },
+ {
+ "end_outermost_loop": 559,
+ "end_region_line": 560,
+ "line": " return 0\n",
+ "lineno": 559,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 559,
+ "start_region_line": 549
+ },
+ {
+ "end_outermost_loop": 560,
+ "end_region_line": 560,
+ "line": " return p\n",
+ "lineno": 560,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 560,
+ "start_region_line": 549
+ },
+ {
+ "end_outermost_loop": 561,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 561,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 561,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 569,
+ "end_region_line": 569,
+ "line": " def get_drive_mode(self):\n",
+ "lineno": 562,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 562,
+ "start_region_line": 562
+ },
+ {
+ "end_outermost_loop": 564,
+ "end_region_line": 569,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 563,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 563,
+ "start_region_line": 562
+ },
+ {
+ "end_outermost_loop": 564,
+ "end_region_line": 569,
+ "line": " return 0\n",
+ "lineno": 564,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 564,
+ "start_region_line": 562
+ },
+ {
+ "end_outermost_loop": 567,
+ "end_region_line": 569,
+ "line": " with self.pt_lock:\n",
+ "lineno": 565,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 565,
+ "start_region_line": 562
+ },
+ {
+ "end_outermost_loop": 567,
+ "end_region_line": 569,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 566,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 566,
+ "start_region_line": 562
+ },
+ {
+ "end_outermost_loop": 567,
+ "end_region_line": 569,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read1ByteTxRx(self.port_handler, self.dxl_id,XL430_ADDR_DRIVE_MODE)\n",
+ "lineno": 567,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 567,
+ "start_region_line": 562
+ },
+ {
+ "end_outermost_loop": 568,
+ "end_region_line": 569,
+ "line": " self.handle_comm_result('XL430_ADDR_DRIVE_MODE', dxl_comm_result, dxl_error)\n",
+ "lineno": 568,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 568,
+ "start_region_line": 562
+ },
+ {
+ "end_outermost_loop": 569,
+ "end_region_line": 569,
+ "line": " return p\n",
+ "lineno": 569,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 569,
+ "start_region_line": 562
+ },
+ {
+ "end_outermost_loop": 570,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 570,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 570,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 583,
+ "end_region_line": 583,
+ "line": " def set_drive_mode(self,vel_based=True, reverse=False):\n",
+ "lineno": 571,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 571,
+ "start_region_line": 571
+ },
+ {
+ "end_outermost_loop": 573,
+ "end_region_line": 583,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 572,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 572,
+ "start_region_line": 571
+ },
+ {
+ "end_outermost_loop": 573,
+ "end_region_line": 583,
+ "line": " return\n",
+ "lineno": 573,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 573,
+ "start_region_line": 571
+ },
+ {
+ "end_outermost_loop": 583,
+ "end_region_line": 583,
+ "line": " #defaults to vel_based, not forward at factory\n",
+ "lineno": 574,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 571,
+ "start_region_line": 571
+ },
+ {
+ "end_outermost_loop": 575,
+ "end_region_line": 583,
+ "line": " x=0\n",
+ "lineno": 575,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 575,
+ "start_region_line": 571
+ },
+ {
+ "end_outermost_loop": 577,
+ "end_region_line": 583,
+ "line": " if not vel_based:\n",
+ "lineno": 576,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 576,
+ "start_region_line": 571
+ },
+ {
+ "end_outermost_loop": 577,
+ "end_region_line": 583,
+ "line": " x=x|0x01\n",
+ "lineno": 577,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 577,
+ "start_region_line": 571
+ },
+ {
+ "end_outermost_loop": 579,
+ "end_region_line": 583,
+ "line": " if reverse:\n",
+ "lineno": 578,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 578,
+ "start_region_line": 571
+ },
+ {
+ "end_outermost_loop": 579,
+ "end_region_line": 583,
+ "line": " x=x|0x4\n",
+ "lineno": 579,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 579,
+ "start_region_line": 571
+ },
+ {
+ "end_outermost_loop": 582,
+ "end_region_line": 583,
+ "line": " with self.pt_lock:\n",
+ "lineno": 580,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 580,
+ "start_region_line": 571
+ },
+ {
+ "end_outermost_loop": 582,
+ "end_region_line": 583,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 581,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 581,
+ "start_region_line": 571
+ },
+ {
+ "end_outermost_loop": 582,
+ "end_region_line": 583,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_DRIVE_MODE, x)\n",
+ "lineno": 582,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 582,
+ "start_region_line": 571
+ },
+ {
+ "end_outermost_loop": 583,
+ "end_region_line": 583,
+ "line": " self.handle_comm_result('XL430_ADDR_DRIVE_MODE', dxl_comm_result, dxl_error)\n",
+ "lineno": 583,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 583,
+ "start_region_line": 571
+ },
+ {
+ "end_outermost_loop": 584,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 584,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 584,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 1035,
+ "end_region_line": 1035,
+ "line": " #XM Series\n",
+ "lineno": 585,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 137,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 590,
+ "end_region_line": 590,
+ "line": " def set_goal_current(self,i):\n",
+ "lineno": 586,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 586,
+ "start_region_line": 586
+ },
+ {
+ "end_outermost_loop": 589,
+ "end_region_line": 590,
+ "line": " with self.pt_lock:\n",
+ "lineno": 587,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 587,
+ "start_region_line": 586
+ },
+ {
+ "end_outermost_loop": 589,
+ "end_region_line": 590,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 588,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 588,
+ "start_region_line": 586
+ },
+ {
+ "end_outermost_loop": 589,
+ "end_region_line": 590,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write2ByteTxRx(self.port_handler, self.dxl_id, XM430_ADDR_GOAL_CURRENT, int(i))\n",
+ "lineno": 589,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 589,
+ "start_region_line": 586
+ },
+ {
+ "end_outermost_loop": 590,
+ "end_region_line": 590,
+ "line": " self.handle_comm_result('XM430_ADDR_GOAL_CURRENT', dxl_comm_result, dxl_error)\n",
+ "lineno": 590,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 590,
+ "start_region_line": 586
+ },
+ {
+ "end_outermost_loop": 591,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 591,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 591,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 600,
+ "end_region_line": 600,
+ "line": " def get_goal_current(self):\n",
+ "lineno": 592,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 592,
+ "start_region_line": 592
+ },
+ {
+ "end_outermost_loop": 594,
+ "end_region_line": 600,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 593,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 593,
+ "start_region_line": 592
+ },
+ {
+ "end_outermost_loop": 594,
+ "end_region_line": 600,
+ "line": " return 0\n",
+ "lineno": 594,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 594,
+ "start_region_line": 592
+ },
+ {
+ "end_outermost_loop": 598,
+ "end_region_line": 600,
+ "line": " with self.pt_lock:\n",
+ "lineno": 595,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 595,
+ "start_region_line": 592
+ },
+ {
+ "end_outermost_loop": 598,
+ "end_region_line": 600,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 596,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 596,
+ "start_region_line": 592
+ },
+ {
+ "end_outermost_loop": 597,
+ "end_region_line": 600,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read2ByteTxRx(self.port_handler, self.dxl_id,\n",
+ "lineno": 597,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 597,
+ "start_region_line": 592
+ },
+ {
+ "end_outermost_loop": 598,
+ "end_region_line": 600,
+ "line": " XM430_ADDR_GOAL_CURRENT)\n",
+ "lineno": 598,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 592
+ },
+ {
+ "end_outermost_loop": 599,
+ "end_region_line": 600,
+ "line": " self.handle_comm_result('XM430_ADDR_GOAL_CURRENT', dxl_comm_result, dxl_error)\n",
+ "lineno": 599,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 599,
+ "start_region_line": 592
+ },
+ {
+ "end_outermost_loop": 600,
+ "end_region_line": 600,
+ "line": " return p\n",
+ "lineno": 600,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 600,
+ "start_region_line": 592
+ },
+ {
+ "end_outermost_loop": 601,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 601,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 601,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 608,
+ "end_region_line": 608,
+ "line": " def go_to_pos(self,x):\n",
+ "lineno": 602,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 602,
+ "start_region_line": 602
+ },
+ {
+ "end_outermost_loop": 604,
+ "end_region_line": 608,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 603,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 603,
+ "start_region_line": 602
+ },
+ {
+ "end_outermost_loop": 604,
+ "end_region_line": 608,
+ "line": " return\n",
+ "lineno": 604,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 604,
+ "start_region_line": 602
+ },
+ {
+ "end_outermost_loop": 607,
+ "end_region_line": 608,
+ "line": " with self.pt_lock:\n",
+ "lineno": 605,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 605,
+ "start_region_line": 602
+ },
+ {
+ "end_outermost_loop": 607,
+ "end_region_line": 608,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 606,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 606,
+ "start_region_line": 602
+ },
+ {
+ "end_outermost_loop": 607,
+ "end_region_line": 608,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write4ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_GOAL_POSITION, int(x))\n",
+ "lineno": 607,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 607,
+ "start_region_line": 602
+ },
+ {
+ "end_outermost_loop": 608,
+ "end_region_line": 608,
+ "line": " self.handle_comm_result('XL430_ADDR_GOAL_POSITION', dxl_comm_result, dxl_error)\n",
+ "lineno": 608,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 608,
+ "start_region_line": 602
+ },
+ {
+ "end_outermost_loop": 609,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 609,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 609,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 615,
+ "end_region_line": 615,
+ "line": " def set_vel(self, x):\n",
+ "lineno": 610,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 610,
+ "start_region_line": 610
+ },
+ {
+ "end_outermost_loop": 614,
+ "end_region_line": 615,
+ "line": " with self.pt_lock:\n",
+ "lineno": 611,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 611,
+ "start_region_line": 610
+ },
+ {
+ "end_outermost_loop": 614,
+ "end_region_line": 615,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 612,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 612,
+ "start_region_line": 610
+ },
+ {
+ "end_outermost_loop": 613,
+ "end_region_line": 615,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write4ByteTxRx(self.port_handler, self.dxl_id,\n",
+ "lineno": 613,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 613,
+ "start_region_line": 610
+ },
+ {
+ "end_outermost_loop": 614,
+ "end_region_line": 615,
+ "line": " XL430_ADDR_GOAL_VEL, int(x))\n",
+ "lineno": 614,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 614,
+ "start_region_line": 610
+ },
+ {
+ "end_outermost_loop": 615,
+ "end_region_line": 615,
+ "line": " self.handle_comm_result('XL430_ADDR_GOAL_VEL', dxl_comm_result, dxl_error)\n",
+ "lineno": 615,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 615,
+ "start_region_line": 610
+ },
+ {
+ "end_outermost_loop": 616,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 616,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 616,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 635,
+ "end_region_line": 635,
+ "line": " def enable_watchdog(self, timeout_20msec=50):\n",
+ "lineno": 617,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 617,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 635,
+ "line": " \"\"\"Enables bus monitoring to stop safely if communications fails.\n",
+ "lineno": 618,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 618,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 619,
+ "end_region_line": 635,
+ "line": "\n",
+ "lineno": 619,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 619,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 620,
+ "end_region_line": 635,
+ "line": " In any operating mode, a watchdog may be enabled on the Dynamixel\n",
+ "lineno": 620,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 620,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 621,
+ "end_region_line": 635,
+ "line": " hardware. If bus communication ceases for longer than a specified\n",
+ "lineno": 621,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 621,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 622,
+ "end_region_line": 635,
+ "line": " timeout, the hardware enters watchdog error mode. New commands will\n",
+ "lineno": 622,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 622,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 623,
+ "end_region_line": 635,
+ "line": " not execute until watchdog is disabled. Watchdog can be used with\n",
+ "lineno": 623,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 623,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 624,
+ "end_region_line": 635,
+ "line": " velocity control to prevent undesired behavior in case of software\n",
+ "lineno": 624,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 624,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 625,
+ "end_region_line": 635,
+ "line": " failure.\n",
+ "lineno": 625,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 625,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 626,
+ "end_region_line": 635,
+ "line": "\n",
+ "lineno": 626,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 626,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 627,
+ "end_region_line": 635,
+ "line": " Parameters\n",
+ "lineno": 627,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 627,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 628,
+ "end_region_line": 635,
+ "line": " ----------\n",
+ "lineno": 628,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 628,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 629,
+ "end_region_line": 635,
+ "line": " timeout_20msec : int\n",
+ "lineno": 629,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 629,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 630,
+ "end_region_line": 635,
+ "line": " value in range [1, 127] calculates timeout as value * 20 milliseconds (default 1s)\n",
+ "lineno": 630,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 630,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 631,
+ "end_region_line": 635,
+ "line": " \"\"\"\n",
+ "lineno": 631,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 631,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 634,
+ "end_region_line": 635,
+ "line": " with self.pt_lock:\n",
+ "lineno": 632,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 632,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 634,
+ "end_region_line": 635,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 633,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 633,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 634,
+ "end_region_line": 635,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_BUS_WATCHDOG, timeout_20msec)\n",
+ "lineno": 634,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 634,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 635,
+ "end_region_line": 635,
+ "line": " self.handle_comm_result('XL430_ADDR_BUS_WATCHDOG', dxl_comm_result, dxl_error)\n",
+ "lineno": 635,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 635,
+ "start_region_line": 617
+ },
+ {
+ "end_outermost_loop": 636,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 636,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 636,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 646,
+ "end_region_line": 646,
+ "line": " def disable_watchdog(self):\n",
+ "lineno": 637,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 637,
+ "start_region_line": 637
+ },
+ {
+ "end_outermost_loop": 638,
+ "end_region_line": 646,
+ "line": " \"\"\"Disables watchdog bus monitoring.\n",
+ "lineno": 638,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 638,
+ "start_region_line": 637
+ },
+ {
+ "end_outermost_loop": 639,
+ "end_region_line": 646,
+ "line": "\n",
+ "lineno": 639,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 639,
+ "start_region_line": 637
+ },
+ {
+ "end_outermost_loop": 640,
+ "end_region_line": 646,
+ "line": " In case of watchdog error occurred, no new goal commands will execute\n",
+ "lineno": 640,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 640,
+ "start_region_line": 637
+ },
+ {
+ "end_outermost_loop": 641,
+ "end_region_line": 646,
+ "line": " until watchdog disabled with this function.\n",
+ "lineno": 641,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 641,
+ "start_region_line": 637
+ },
+ {
+ "end_outermost_loop": 642,
+ "end_region_line": 646,
+ "line": " \"\"\"\n",
+ "lineno": 642,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 642,
+ "start_region_line": 637
+ },
+ {
+ "end_outermost_loop": 645,
+ "end_region_line": 646,
+ "line": " with self.pt_lock:\n",
+ "lineno": 643,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 643,
+ "start_region_line": 637
+ },
+ {
+ "end_outermost_loop": 645,
+ "end_region_line": 646,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 644,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 644,
+ "start_region_line": 637
+ },
+ {
+ "end_outermost_loop": 645,
+ "end_region_line": 646,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_BUS_WATCHDOG, 0)\n",
+ "lineno": 645,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 645,
+ "start_region_line": 637
+ },
+ {
+ "end_outermost_loop": 646,
+ "end_region_line": 646,
+ "line": " self.handle_comm_result('XL430_ADDR_BUS_WATCHDOG', dxl_comm_result, dxl_error)\n",
+ "lineno": 646,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 646,
+ "start_region_line": 637
+ },
+ {
+ "end_outermost_loop": 647,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 647,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 647,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 660,
+ "end_region_line": 660,
+ "line": " def get_watchdog_error(self):\n",
+ "lineno": 648,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 648,
+ "start_region_line": 648
+ },
+ {
+ "end_outermost_loop": 649,
+ "end_region_line": 660,
+ "line": " \"\"\"Checks if watchdog error occurred.\n",
+ "lineno": 649,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 649,
+ "start_region_line": 648
+ },
+ {
+ "end_outermost_loop": 650,
+ "end_region_line": 660,
+ "line": "\n",
+ "lineno": 650,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 650,
+ "start_region_line": 648
+ },
+ {
+ "end_outermost_loop": 651,
+ "end_region_line": 660,
+ "line": " Returns\n",
+ "lineno": 651,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 651,
+ "start_region_line": 648
+ },
+ {
+ "end_outermost_loop": 652,
+ "end_region_line": 660,
+ "line": " -------\n",
+ "lineno": 652,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 652,
+ "start_region_line": 648
+ },
+ {
+ "end_outermost_loop": 653,
+ "end_region_line": 660,
+ "line": " bool\n",
+ "lineno": 653,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 653,
+ "start_region_line": 648
+ },
+ {
+ "end_outermost_loop": 654,
+ "end_region_line": 660,
+ "line": " True if watchdog detected no communication for longer than watchdog timeout\n",
+ "lineno": 654,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 654,
+ "start_region_line": 648
+ },
+ {
+ "end_outermost_loop": 655,
+ "end_region_line": 660,
+ "line": " \"\"\"\n",
+ "lineno": 655,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 655,
+ "start_region_line": 648
+ },
+ {
+ "end_outermost_loop": 658,
+ "end_region_line": 660,
+ "line": " with self.pt_lock:\n",
+ "lineno": 656,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 656,
+ "start_region_line": 648
+ },
+ {
+ "end_outermost_loop": 658,
+ "end_region_line": 660,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 657,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 657,
+ "start_region_line": 648
+ },
+ {
+ "end_outermost_loop": 658,
+ "end_region_line": 660,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_BUS_WATCHDOG)\n",
+ "lineno": 658,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 658,
+ "start_region_line": 648
+ },
+ {
+ "end_outermost_loop": 659,
+ "end_region_line": 660,
+ "line": " self.handle_comm_result('XL430_ADDR_BUS_WATCHDOG', dxl_comm_result, dxl_error)\n",
+ "lineno": 659,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 659,
+ "start_region_line": 648
+ },
+ {
+ "end_outermost_loop": 660,
+ "end_region_line": 660,
+ "line": " return p == 255\n",
+ "lineno": 660,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 660,
+ "start_region_line": 648
+ },
+ {
+ "end_outermost_loop": 661,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 661,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 661,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 669,
+ "end_region_line": 669,
+ "line": " def get_current(self):\n",
+ "lineno": 662,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 662,
+ "start_region_line": 662
+ },
+ {
+ "end_outermost_loop": 664,
+ "end_region_line": 669,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 663,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 663,
+ "start_region_line": 662
+ },
+ {
+ "end_outermost_loop": 664,
+ "end_region_line": 669,
+ "line": " return 0\n",
+ "lineno": 664,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 664,
+ "start_region_line": 662
+ },
+ {
+ "end_outermost_loop": 667,
+ "end_region_line": 669,
+ "line": " with self.pt_lock:\n",
+ "lineno": 665,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 665,
+ "start_region_line": 662
+ },
+ {
+ "end_outermost_loop": 667,
+ "end_region_line": 669,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 666,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 666,
+ "start_region_line": 662
+ },
+ {
+ "end_outermost_loop": 667,
+ "end_region_line": 669,
+ "line": " xn, dxl_comm_result, dxl_error= self.read_int16_t(XM430_ADDR_PRESENT_CURRENT)\n",
+ "lineno": 667,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 667,
+ "start_region_line": 662
+ },
+ {
+ "end_outermost_loop": 668,
+ "end_region_line": 669,
+ "line": " self.handle_comm_result('XM430_ADDR_PRESENT_CURRENT', dxl_comm_result, dxl_error)\n",
+ "lineno": 668,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 668,
+ "start_region_line": 662
+ },
+ {
+ "end_outermost_loop": 669,
+ "end_region_line": 669,
+ "line": " return xn\n",
+ "lineno": 669,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 669,
+ "start_region_line": 662
+ },
+ {
+ "end_outermost_loop": 670,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 670,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 670,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 678,
+ "end_region_line": 678,
+ "line": " def get_pos(self):\n",
+ "lineno": 671,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 671,
+ "start_region_line": 671
+ },
+ {
+ "end_outermost_loop": 673,
+ "end_region_line": 678,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 672,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 672,
+ "start_region_line": 671
+ },
+ {
+ "end_outermost_loop": 673,
+ "end_region_line": 678,
+ "line": " return 0\n",
+ "lineno": 673,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 673,
+ "start_region_line": 671
+ },
+ {
+ "end_outermost_loop": 676,
+ "end_region_line": 678,
+ "line": " with self.pt_lock:\n",
+ "lineno": 674,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 674,
+ "start_region_line": 671
+ },
+ {
+ "end_outermost_loop": 676,
+ "end_region_line": 678,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 675,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 675,
+ "start_region_line": 671
+ },
+ {
+ "end_outermost_loop": 676,
+ "end_region_line": 678,
+ "line": " xn, dxl_comm_result, dxl_error= self.read_int32_t(XL430_ADDR_PRESENT_POSITION)\n",
+ "lineno": 676,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 676,
+ "start_region_line": 671
+ },
+ {
+ "end_outermost_loop": 677,
+ "end_region_line": 678,
+ "line": " self.handle_comm_result('XL430_ADDR_PRESENT_POSITION', dxl_comm_result, dxl_error)\n",
+ "lineno": 677,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 677,
+ "start_region_line": 671
+ },
+ {
+ "end_outermost_loop": 678,
+ "end_region_line": 678,
+ "line": " return xn\n",
+ "lineno": 678,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 678,
+ "start_region_line": 671
+ },
+ {
+ "end_outermost_loop": 679,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 679,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 679,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 687,
+ "end_region_line": 687,
+ "line": " def get_moving_status(self):\n",
+ "lineno": 680,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 680,
+ "start_region_line": 680
+ },
+ {
+ "end_outermost_loop": 682,
+ "end_region_line": 687,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 681,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 681,
+ "start_region_line": 680
+ },
+ {
+ "end_outermost_loop": 682,
+ "end_region_line": 687,
+ "line": " return\n",
+ "lineno": 682,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 682,
+ "start_region_line": 680
+ },
+ {
+ "end_outermost_loop": 685,
+ "end_region_line": 687,
+ "line": " with self.pt_lock:\n",
+ "lineno": 683,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 683,
+ "start_region_line": 680
+ },
+ {
+ "end_outermost_loop": 685,
+ "end_region_line": 687,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 684,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 684,
+ "start_region_line": 680
+ },
+ {
+ "end_outermost_loop": 685,
+ "end_region_line": 687,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_MOVING_STATUS)\n",
+ "lineno": 685,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 685,
+ "start_region_line": 680
+ },
+ {
+ "end_outermost_loop": 686,
+ "end_region_line": 687,
+ "line": " self.handle_comm_result('XL430_ADDR_MOVING_STATUS', dxl_comm_result, dxl_error)\n",
+ "lineno": 686,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 686,
+ "start_region_line": 680
+ },
+ {
+ "end_outermost_loop": 687,
+ "end_region_line": 687,
+ "line": " return p\n",
+ "lineno": 687,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 687,
+ "start_region_line": 680
+ },
+ {
+ "end_outermost_loop": 688,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 688,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 688,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 696,
+ "end_region_line": 696,
+ "line": " def get_load(self):\n",
+ "lineno": 689,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 689,
+ "start_region_line": 689
+ },
+ {
+ "end_outermost_loop": 691,
+ "end_region_line": 696,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 690,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 690,
+ "start_region_line": 689
+ },
+ {
+ "end_outermost_loop": 691,
+ "end_region_line": 696,
+ "line": " return 0\n",
+ "lineno": 691,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 691,
+ "start_region_line": 689
+ },
+ {
+ "end_outermost_loop": 694,
+ "end_region_line": 696,
+ "line": " with self.pt_lock:\n",
+ "lineno": 692,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 692,
+ "start_region_line": 689
+ },
+ {
+ "end_outermost_loop": 694,
+ "end_region_line": 696,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 693,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 693,
+ "start_region_line": 689
+ },
+ {
+ "end_outermost_loop": 694,
+ "end_region_line": 696,
+ "line": " xn, dxl_comm_result, dxl_error= self.read_int16_t(XL430_ADDR_PRESENT_LOAD)\n",
+ "lineno": 694,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 694,
+ "start_region_line": 689
+ },
+ {
+ "end_outermost_loop": 695,
+ "end_region_line": 696,
+ "line": " self.handle_comm_result('XL430_ADDR_PRESENT_LOAD', dxl_comm_result, dxl_error)\n",
+ "lineno": 695,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 695,
+ "start_region_line": 689
+ },
+ {
+ "end_outermost_loop": 696,
+ "end_region_line": 696,
+ "line": " return xn\n",
+ "lineno": 696,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 696,
+ "start_region_line": 689
+ },
+ {
+ "end_outermost_loop": 697,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 697,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 697,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 705,
+ "end_region_line": 705,
+ "line": " def get_pwm(self):\n",
+ "lineno": 698,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 698,
+ "start_region_line": 698
+ },
+ {
+ "end_outermost_loop": 700,
+ "end_region_line": 705,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 699,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 699,
+ "start_region_line": 698
+ },
+ {
+ "end_outermost_loop": 700,
+ "end_region_line": 705,
+ "line": " return 0\n",
+ "lineno": 700,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 700,
+ "start_region_line": 698
+ },
+ {
+ "end_outermost_loop": 703,
+ "end_region_line": 705,
+ "line": " with self.pt_lock:\n",
+ "lineno": 701,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 701,
+ "start_region_line": 698
+ },
+ {
+ "end_outermost_loop": 703,
+ "end_region_line": 705,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 702,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 702,
+ "start_region_line": 698
+ },
+ {
+ "end_outermost_loop": 703,
+ "end_region_line": 705,
+ "line": " xn, dxl_comm_result, dxl_error= self.read_int16_t(XL430_ADDR_PRESENT_PWM)\n",
+ "lineno": 703,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 703,
+ "start_region_line": 698
+ },
+ {
+ "end_outermost_loop": 704,
+ "end_region_line": 705,
+ "line": " self.handle_comm_result('XL430_ADDR_PRESENT_PWM', dxl_comm_result, dxl_error)\n",
+ "lineno": 704,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 704,
+ "start_region_line": 698
+ },
+ {
+ "end_outermost_loop": 705,
+ "end_region_line": 705,
+ "line": " return xn\n",
+ "lineno": 705,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 705,
+ "start_region_line": 698
+ },
+ {
+ "end_outermost_loop": 706,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 706,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 706,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 717,
+ "end_region_line": 717,
+ "line": " def set_profile_velocity(self,v):\n",
+ "lineno": 707,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 707,
+ "start_region_line": 707
+ },
+ {
+ "end_outermost_loop": 709,
+ "end_region_line": 717,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 708,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 708,
+ "start_region_line": 707
+ },
+ {
+ "end_outermost_loop": 709,
+ "end_region_line": 717,
+ "line": " return\n",
+ "lineno": 709,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 709,
+ "start_region_line": 707
+ },
+ {
+ "end_outermost_loop": 713,
+ "end_region_line": 717,
+ "line": " if abs(v)\\u003c1:\n",
+ "lineno": 710,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 710,
+ "start_region_line": 707
+ },
+ {
+ "end_outermost_loop": 713,
+ "end_region_line": 717,
+ "line": " # Dxls assumes Zero ticks/s as infinite/max velocity which is counterintutive\n",
+ "lineno": 711,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 710,
+ "start_region_line": 707
+ },
+ {
+ "end_outermost_loop": 713,
+ "end_region_line": 717,
+ "line": " # Therefore setting a zero will assign to the lowest possible velocity 1 ticks/s\n",
+ "lineno": 712,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 710,
+ "start_region_line": 707
+ },
+ {
+ "end_outermost_loop": 713,
+ "end_region_line": 717,
+ "line": " v = 1\n",
+ "lineno": 713,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 713,
+ "start_region_line": 707
+ },
+ {
+ "end_outermost_loop": 716,
+ "end_region_line": 717,
+ "line": " with self.pt_lock:\n",
+ "lineno": 714,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 714,
+ "start_region_line": 707
+ },
+ {
+ "end_outermost_loop": 716,
+ "end_region_line": 717,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 715,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 715,
+ "start_region_line": 707
+ },
+ {
+ "end_outermost_loop": 716,
+ "end_region_line": 717,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write4ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_PROFILE_VELOCITY, int(v))\n",
+ "lineno": 716,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 716,
+ "start_region_line": 707
+ },
+ {
+ "end_outermost_loop": 717,
+ "end_region_line": 717,
+ "line": " self.handle_comm_result('XL430_ADDR_PROFILE_VELOCITY', dxl_comm_result, dxl_error)\n",
+ "lineno": 717,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 717,
+ "start_region_line": 707
+ },
+ {
+ "end_outermost_loop": 718,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 718,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 718,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 729,
+ "end_region_line": 729,
+ "line": " def set_profile_acceleration(self, a):\n",
+ "lineno": 719,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 719,
+ "start_region_line": 719
+ },
+ {
+ "end_outermost_loop": 721,
+ "end_region_line": 729,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 720,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 720,
+ "start_region_line": 719
+ },
+ {
+ "end_outermost_loop": 721,
+ "end_region_line": 729,
+ "line": " return\n",
+ "lineno": 721,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 721,
+ "start_region_line": 719
+ },
+ {
+ "end_outermost_loop": 725,
+ "end_region_line": 729,
+ "line": " if abs(a)\\u003c1:\n",
+ "lineno": 722,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 722,
+ "start_region_line": 719
+ },
+ {
+ "end_outermost_loop": 725,
+ "end_region_line": 729,
+ "line": " # Dxls assumes Zero ticks/s^2 as infinite/max acceleration which is counterintutive\n",
+ "lineno": 723,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 722,
+ "start_region_line": 719
+ },
+ {
+ "end_outermost_loop": 725,
+ "end_region_line": 729,
+ "line": " # Therefore setting a zero will assign to the lowest possible acceleration 1 ticks/s^2\n",
+ "lineno": 724,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 722,
+ "start_region_line": 719
+ },
+ {
+ "end_outermost_loop": 725,
+ "end_region_line": 729,
+ "line": " a = 1\n",
+ "lineno": 725,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 725,
+ "start_region_line": 719
+ },
+ {
+ "end_outermost_loop": 728,
+ "end_region_line": 729,
+ "line": " with self.pt_lock:\n",
+ "lineno": 726,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 726,
+ "start_region_line": 719
+ },
+ {
+ "end_outermost_loop": 728,
+ "end_region_line": 729,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 727,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 727,
+ "start_region_line": 719
+ },
+ {
+ "end_outermost_loop": 728,
+ "end_region_line": 729,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write4ByteTxRx(self.port_handler, self.dxl_id,XL430_ADDR_PROFILE_ACCELERATION, int(a))\n",
+ "lineno": 728,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 728,
+ "start_region_line": 719
+ },
+ {
+ "end_outermost_loop": 729,
+ "end_region_line": 729,
+ "line": " self.handle_comm_result('XL430_ADDR_PROFILE_ACCELERATION', dxl_comm_result, dxl_error)\n",
+ "lineno": 729,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 729,
+ "start_region_line": 719
+ },
+ {
+ "end_outermost_loop": 730,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 730,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 730,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 731,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 731,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 731,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 739,
+ "end_region_line": 739,
+ "line": " def get_profile_velocity(self):\n",
+ "lineno": 732,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 732,
+ "start_region_line": 732
+ },
+ {
+ "end_outermost_loop": 734,
+ "end_region_line": 739,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 733,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 733,
+ "start_region_line": 732
+ },
+ {
+ "end_outermost_loop": 734,
+ "end_region_line": 739,
+ "line": " return 0\n",
+ "lineno": 734,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 734,
+ "start_region_line": 732
+ },
+ {
+ "end_outermost_loop": 737,
+ "end_region_line": 739,
+ "line": " with self.pt_lock:\n",
+ "lineno": 735,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 735,
+ "start_region_line": 732
+ },
+ {
+ "end_outermost_loop": 737,
+ "end_region_line": 739,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 736,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 736,
+ "start_region_line": 732
+ },
+ {
+ "end_outermost_loop": 737,
+ "end_region_line": 739,
+ "line": " v, dxl_comm_result, dxl_error = self.packet_handler.read4ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_PROFILE_VELOCITY)\n",
+ "lineno": 737,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 737,
+ "start_region_line": 732
+ },
+ {
+ "end_outermost_loop": 738,
+ "end_region_line": 739,
+ "line": " self.handle_comm_result('XL430_ADDR_PROFILE_VELOCITY', dxl_comm_result, dxl_error)\n",
+ "lineno": 738,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 738,
+ "start_region_line": 732
+ },
+ {
+ "end_outermost_loop": 739,
+ "end_region_line": 739,
+ "line": " return v\n",
+ "lineno": 739,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 739,
+ "start_region_line": 732
+ },
+ {
+ "end_outermost_loop": 740,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 740,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 740,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 748,
+ "end_region_line": 748,
+ "line": " def get_profile_acceleration(self):\n",
+ "lineno": 741,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 741,
+ "start_region_line": 741
+ },
+ {
+ "end_outermost_loop": 743,
+ "end_region_line": 748,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 742,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 742,
+ "start_region_line": 741
+ },
+ {
+ "end_outermost_loop": 743,
+ "end_region_line": 748,
+ "line": " return 0\n",
+ "lineno": 743,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 743,
+ "start_region_line": 741
+ },
+ {
+ "end_outermost_loop": 746,
+ "end_region_line": 748,
+ "line": " with self.pt_lock:\n",
+ "lineno": 744,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 744,
+ "start_region_line": 741
+ },
+ {
+ "end_outermost_loop": 746,
+ "end_region_line": 748,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 745,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 745,
+ "start_region_line": 741
+ },
+ {
+ "end_outermost_loop": 746,
+ "end_region_line": 748,
+ "line": " a, dxl_comm_result, dxl_error = self.packet_handler.read4ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_PROFILE_ACCELERATION)\n",
+ "lineno": 746,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 746,
+ "start_region_line": 741
+ },
+ {
+ "end_outermost_loop": 747,
+ "end_region_line": 748,
+ "line": " self.handle_comm_result('XL430_ADDR_PROFILE_ACCELERATION', dxl_comm_result, dxl_error)\n",
+ "lineno": 747,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 747,
+ "start_region_line": 741
+ },
+ {
+ "end_outermost_loop": 748,
+ "end_region_line": 748,
+ "line": " return a\n",
+ "lineno": 748,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 748,
+ "start_region_line": 741
+ },
+ {
+ "end_outermost_loop": 749,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 749,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 749,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 759,
+ "end_region_line": 759,
+ "line": " def get_vel(self):\n",
+ "lineno": 750,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 750,
+ "start_region_line": 750
+ },
+ {
+ "end_outermost_loop": 752,
+ "end_region_line": 759,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 751,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 751,
+ "start_region_line": 750
+ },
+ {
+ "end_outermost_loop": 752,
+ "end_region_line": 759,
+ "line": " return 0\n",
+ "lineno": 752,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 752,
+ "start_region_line": 750
+ },
+ {
+ "end_outermost_loop": 755,
+ "end_region_line": 759,
+ "line": " with self.pt_lock:\n",
+ "lineno": 753,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 753,
+ "start_region_line": 750
+ },
+ {
+ "end_outermost_loop": 755,
+ "end_region_line": 759,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 754,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 754,
+ "start_region_line": 750
+ },
+ {
+ "end_outermost_loop": 755,
+ "end_region_line": 759,
+ "line": " v, dxl_comm_result, dxl_error = self.packet_handler.read4ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_PRESENT_VELOCITY)\n",
+ "lineno": 755,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 755,
+ "start_region_line": 750
+ },
+ {
+ "end_outermost_loop": 756,
+ "end_region_line": 759,
+ "line": " self.handle_comm_result('XL430_ADDR_PRESENT_VELOCITY', dxl_comm_result, dxl_error)\n",
+ "lineno": 756,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 756,
+ "start_region_line": 750
+ },
+ {
+ "end_outermost_loop": 758,
+ "end_region_line": 759,
+ "line": " if v \\u003e 2 ** 24:\n",
+ "lineno": 757,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 757,
+ "start_region_line": 750
+ },
+ {
+ "end_outermost_loop": 758,
+ "end_region_line": 759,
+ "line": " v = v - 2 ** 32\n",
+ "lineno": 758,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 758,
+ "start_region_line": 750
+ },
+ {
+ "end_outermost_loop": 759,
+ "end_region_line": 759,
+ "line": " return v\n",
+ "lineno": 759,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 759,
+ "start_region_line": 750
+ },
+ {
+ "end_outermost_loop": 760,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 760,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 760,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 768,
+ "end_region_line": 768,
+ "line": " def get_P_gain(self):\n",
+ "lineno": 761,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 761,
+ "start_region_line": 761
+ },
+ {
+ "end_outermost_loop": 763,
+ "end_region_line": 768,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 762,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 762,
+ "start_region_line": 761
+ },
+ {
+ "end_outermost_loop": 763,
+ "end_region_line": 768,
+ "line": " return 0\n",
+ "lineno": 763,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 763,
+ "start_region_line": 761
+ },
+ {
+ "end_outermost_loop": 766,
+ "end_region_line": 768,
+ "line": " with self.pt_lock:\n",
+ "lineno": 764,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 764,
+ "start_region_line": 761
+ },
+ {
+ "end_outermost_loop": 766,
+ "end_region_line": 768,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 765,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 765,
+ "start_region_line": 761
+ },
+ {
+ "end_outermost_loop": 766,
+ "end_region_line": 768,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read2ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_POS_P_GAIN)\n",
+ "lineno": 766,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 766,
+ "start_region_line": 761
+ },
+ {
+ "end_outermost_loop": 767,
+ "end_region_line": 768,
+ "line": " self.handle_comm_result('XL430_ADDR_POS_P_GAIN', dxl_comm_result, dxl_error)\n",
+ "lineno": 767,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 767,
+ "start_region_line": 761
+ },
+ {
+ "end_outermost_loop": 768,
+ "end_region_line": 768,
+ "line": " return p\n",
+ "lineno": 768,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 768,
+ "start_region_line": 761
+ },
+ {
+ "end_outermost_loop": 769,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 769,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 769,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 776,
+ "end_region_line": 776,
+ "line": " def set_P_gain(self,x):\n",
+ "lineno": 770,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 770,
+ "start_region_line": 770
+ },
+ {
+ "end_outermost_loop": 772,
+ "end_region_line": 776,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 771,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 771,
+ "start_region_line": 770
+ },
+ {
+ "end_outermost_loop": 772,
+ "end_region_line": 776,
+ "line": " return\n",
+ "lineno": 772,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 772,
+ "start_region_line": 770
+ },
+ {
+ "end_outermost_loop": 775,
+ "end_region_line": 776,
+ "line": " with self.pt_lock:\n",
+ "lineno": 773,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 773,
+ "start_region_line": 770
+ },
+ {
+ "end_outermost_loop": 775,
+ "end_region_line": 776,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 774,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 774,
+ "start_region_line": 770
+ },
+ {
+ "end_outermost_loop": 775,
+ "end_region_line": 776,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write2ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_POS_P_GAIN, int(x))\n",
+ "lineno": 775,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 775,
+ "start_region_line": 770
+ },
+ {
+ "end_outermost_loop": 776,
+ "end_region_line": 776,
+ "line": " self.handle_comm_result('XL430_ADDR_POS_P_GAIN', dxl_comm_result, dxl_error)\n",
+ "lineno": 776,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 776,
+ "start_region_line": 770
+ },
+ {
+ "end_outermost_loop": 777,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 777,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 777,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 785,
+ "end_region_line": 785,
+ "line": " def get_D_gain(self):\n",
+ "lineno": 778,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 778,
+ "start_region_line": 778
+ },
+ {
+ "end_outermost_loop": 780,
+ "end_region_line": 785,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 779,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 779,
+ "start_region_line": 778
+ },
+ {
+ "end_outermost_loop": 780,
+ "end_region_line": 785,
+ "line": " return 0\n",
+ "lineno": 780,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 780,
+ "start_region_line": 778
+ },
+ {
+ "end_outermost_loop": 783,
+ "end_region_line": 785,
+ "line": " with self.pt_lock:\n",
+ "lineno": 781,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 781,
+ "start_region_line": 778
+ },
+ {
+ "end_outermost_loop": 783,
+ "end_region_line": 785,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 782,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 782,
+ "start_region_line": 778
+ },
+ {
+ "end_outermost_loop": 783,
+ "end_region_line": 785,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read2ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_POS_D_GAIN)\n",
+ "lineno": 783,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 783,
+ "start_region_line": 778
+ },
+ {
+ "end_outermost_loop": 784,
+ "end_region_line": 785,
+ "line": " self.handle_comm_result('XL430_ADDR_POS_D_GAIN', dxl_comm_result, dxl_error)\n",
+ "lineno": 784,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 784,
+ "start_region_line": 778
+ },
+ {
+ "end_outermost_loop": 785,
+ "end_region_line": 785,
+ "line": " return p\n",
+ "lineno": 785,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 785,
+ "start_region_line": 778
+ },
+ {
+ "end_outermost_loop": 786,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 786,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 786,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 793,
+ "end_region_line": 793,
+ "line": " def set_D_gain(self,x):\n",
+ "lineno": 787,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 787,
+ "start_region_line": 787
+ },
+ {
+ "end_outermost_loop": 789,
+ "end_region_line": 793,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 788,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 788,
+ "start_region_line": 787
+ },
+ {
+ "end_outermost_loop": 789,
+ "end_region_line": 793,
+ "line": " return\n",
+ "lineno": 789,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 789,
+ "start_region_line": 787
+ },
+ {
+ "end_outermost_loop": 792,
+ "end_region_line": 793,
+ "line": " with self.pt_lock:\n",
+ "lineno": 790,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 790,
+ "start_region_line": 787
+ },
+ {
+ "end_outermost_loop": 792,
+ "end_region_line": 793,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 791,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 791,
+ "start_region_line": 787
+ },
+ {
+ "end_outermost_loop": 792,
+ "end_region_line": 793,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write2ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_POS_D_GAIN, int(x))\n",
+ "lineno": 792,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 792,
+ "start_region_line": 787
+ },
+ {
+ "end_outermost_loop": 793,
+ "end_region_line": 793,
+ "line": " self.handle_comm_result('XL430_ADDR_POS_D_GAIN', dxl_comm_result, dxl_error)\n",
+ "lineno": 793,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 793,
+ "start_region_line": 787
+ },
+ {
+ "end_outermost_loop": 794,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 794,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 794,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 802,
+ "end_region_line": 802,
+ "line": " def get_I_gain(self):\n",
+ "lineno": 795,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 795,
+ "start_region_line": 795
+ },
+ {
+ "end_outermost_loop": 797,
+ "end_region_line": 802,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 796,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 796,
+ "start_region_line": 795
+ },
+ {
+ "end_outermost_loop": 797,
+ "end_region_line": 802,
+ "line": " return 0\n",
+ "lineno": 797,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 797,
+ "start_region_line": 795
+ },
+ {
+ "end_outermost_loop": 800,
+ "end_region_line": 802,
+ "line": " with self.pt_lock:\n",
+ "lineno": 798,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 798,
+ "start_region_line": 795
+ },
+ {
+ "end_outermost_loop": 800,
+ "end_region_line": 802,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 799,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 799,
+ "start_region_line": 795
+ },
+ {
+ "end_outermost_loop": 800,
+ "end_region_line": 802,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read2ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_POS_I_GAIN)\n",
+ "lineno": 800,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 800,
+ "start_region_line": 795
+ },
+ {
+ "end_outermost_loop": 801,
+ "end_region_line": 802,
+ "line": " self.handle_comm_result('XL430_ADDR_POS_I_GAIN', dxl_comm_result, dxl_error)\n",
+ "lineno": 801,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 801,
+ "start_region_line": 795
+ },
+ {
+ "end_outermost_loop": 802,
+ "end_region_line": 802,
+ "line": " return p\n",
+ "lineno": 802,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 802,
+ "start_region_line": 795
+ },
+ {
+ "end_outermost_loop": 803,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 803,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 803,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 810,
+ "end_region_line": 810,
+ "line": " def set_I_gain(self,x):\n",
+ "lineno": 804,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 804,
+ "start_region_line": 804
+ },
+ {
+ "end_outermost_loop": 806,
+ "end_region_line": 810,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 805,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 805,
+ "start_region_line": 804
+ },
+ {
+ "end_outermost_loop": 806,
+ "end_region_line": 810,
+ "line": " return\n",
+ "lineno": 806,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 806,
+ "start_region_line": 804
+ },
+ {
+ "end_outermost_loop": 809,
+ "end_region_line": 810,
+ "line": " with self.pt_lock:\n",
+ "lineno": 807,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 807,
+ "start_region_line": 804
+ },
+ {
+ "end_outermost_loop": 809,
+ "end_region_line": 810,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 808,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 808,
+ "start_region_line": 804
+ },
+ {
+ "end_outermost_loop": 809,
+ "end_region_line": 810,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write2ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_POS_I_GAIN, int(x))\n",
+ "lineno": 809,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 27.287861693500293,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 809,
+ "start_region_line": 804
+ },
+ {
+ "end_outermost_loop": 810,
+ "end_region_line": 810,
+ "line": " self.handle_comm_result('XL430_ADDR_POS_I_GAIN', dxl_comm_result, dxl_error)\n",
+ "lineno": 810,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 810,
+ "start_region_line": 804
+ },
+ {
+ "end_outermost_loop": 811,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 811,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 811,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 819,
+ "end_region_line": 819,
+ "line": " def get_vel_I_gain(self):\n",
+ "lineno": 812,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 812,
+ "start_region_line": 812
+ },
+ {
+ "end_outermost_loop": 814,
+ "end_region_line": 819,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 813,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 813,
+ "start_region_line": 812
+ },
+ {
+ "end_outermost_loop": 814,
+ "end_region_line": 819,
+ "line": " return 0\n",
+ "lineno": 814,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 814,
+ "start_region_line": 812
+ },
+ {
+ "end_outermost_loop": 817,
+ "end_region_line": 819,
+ "line": " with self.pt_lock:\n",
+ "lineno": 815,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 815,
+ "start_region_line": 812
+ },
+ {
+ "end_outermost_loop": 817,
+ "end_region_line": 819,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 816,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 816,
+ "start_region_line": 812
+ },
+ {
+ "end_outermost_loop": 817,
+ "end_region_line": 819,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read2ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_VELOCITY_I_GAIN)\n",
+ "lineno": 817,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 817,
+ "start_region_line": 812
+ },
+ {
+ "end_outermost_loop": 818,
+ "end_region_line": 819,
+ "line": " self.handle_comm_result('XL430_ADDR_VELOCITY_I_GAIN', dxl_comm_result, dxl_error)\n",
+ "lineno": 818,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 818,
+ "start_region_line": 812
+ },
+ {
+ "end_outermost_loop": 819,
+ "end_region_line": 819,
+ "line": " return p\n",
+ "lineno": 819,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 819,
+ "start_region_line": 812
+ },
+ {
+ "end_outermost_loop": 820,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 820,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 820,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 827,
+ "end_region_line": 827,
+ "line": " def set_vel_I_gain(self,x):\n",
+ "lineno": 821,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 821,
+ "start_region_line": 821
+ },
+ {
+ "end_outermost_loop": 823,
+ "end_region_line": 827,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 822,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 822,
+ "start_region_line": 821
+ },
+ {
+ "end_outermost_loop": 823,
+ "end_region_line": 827,
+ "line": " return\n",
+ "lineno": 823,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 823,
+ "start_region_line": 821
+ },
+ {
+ "end_outermost_loop": 826,
+ "end_region_line": 827,
+ "line": " with self.pt_lock:\n",
+ "lineno": 824,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 824,
+ "start_region_line": 821
+ },
+ {
+ "end_outermost_loop": 826,
+ "end_region_line": 827,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 825,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 825,
+ "start_region_line": 821
+ },
+ {
+ "end_outermost_loop": 826,
+ "end_region_line": 827,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write2ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_VELOCITY_I_GAIN, int(x))\n",
+ "lineno": 826,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 826,
+ "start_region_line": 821
+ },
+ {
+ "end_outermost_loop": 827,
+ "end_region_line": 827,
+ "line": " self.handle_comm_result('XL430_ADDR_VELOCITY_I_GAIN', dxl_comm_result, dxl_error)\n",
+ "lineno": 827,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 827,
+ "start_region_line": 821
+ },
+ {
+ "end_outermost_loop": 828,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 828,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 828,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 836,
+ "end_region_line": 836,
+ "line": " def get_vel_P_gain(self):\n",
+ "lineno": 829,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 829,
+ "start_region_line": 829
+ },
+ {
+ "end_outermost_loop": 831,
+ "end_region_line": 836,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 830,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 830,
+ "start_region_line": 829
+ },
+ {
+ "end_outermost_loop": 831,
+ "end_region_line": 836,
+ "line": " return 0\n",
+ "lineno": 831,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 831,
+ "start_region_line": 829
+ },
+ {
+ "end_outermost_loop": 834,
+ "end_region_line": 836,
+ "line": " with self.pt_lock:\n",
+ "lineno": 832,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 832,
+ "start_region_line": 829
+ },
+ {
+ "end_outermost_loop": 834,
+ "end_region_line": 836,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 833,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 833,
+ "start_region_line": 829
+ },
+ {
+ "end_outermost_loop": 834,
+ "end_region_line": 836,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read2ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_VELOCITY_P_GAIN)\n",
+ "lineno": 834,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 834,
+ "start_region_line": 829
+ },
+ {
+ "end_outermost_loop": 835,
+ "end_region_line": 836,
+ "line": " self.handle_comm_result('XL430_ADDR_VELOCITY_P_GAIN', dxl_comm_result, dxl_error)\n",
+ "lineno": 835,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 835,
+ "start_region_line": 829
+ },
+ {
+ "end_outermost_loop": 836,
+ "end_region_line": 836,
+ "line": " return p\n",
+ "lineno": 836,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 836,
+ "start_region_line": 829
+ },
+ {
+ "end_outermost_loop": 837,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 837,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 837,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 844,
+ "end_region_line": 844,
+ "line": " def set_vel_P_gain(self,x):\n",
+ "lineno": 838,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 838,
+ "start_region_line": 838
+ },
+ {
+ "end_outermost_loop": 840,
+ "end_region_line": 844,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 839,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 839,
+ "start_region_line": 838
+ },
+ {
+ "end_outermost_loop": 840,
+ "end_region_line": 844,
+ "line": " return\n",
+ "lineno": 840,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 840,
+ "start_region_line": 838
+ },
+ {
+ "end_outermost_loop": 843,
+ "end_region_line": 844,
+ "line": " with self.pt_lock:\n",
+ "lineno": 841,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 841,
+ "start_region_line": 838
+ },
+ {
+ "end_outermost_loop": 843,
+ "end_region_line": 844,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 842,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 842,
+ "start_region_line": 838
+ },
+ {
+ "end_outermost_loop": 843,
+ "end_region_line": 844,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write2ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_VELOCITY_P_GAIN, int(x))\n",
+ "lineno": 843,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 843,
+ "start_region_line": 838
+ },
+ {
+ "end_outermost_loop": 844,
+ "end_region_line": 844,
+ "line": " self.handle_comm_result('XL430_ADDR_VELOCITY_P_GAIN', dxl_comm_result, dxl_error)\n",
+ "lineno": 844,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 844,
+ "start_region_line": 838
+ },
+ {
+ "end_outermost_loop": 845,
+ "end_region_line": 1035,
+ "line": " \n",
+ "lineno": 845,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 845,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 853,
+ "end_region_line": 853,
+ "line": " def get_temperature_limit(self):\n",
+ "lineno": 846,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 846,
+ "start_region_line": 846
+ },
+ {
+ "end_outermost_loop": 848,
+ "end_region_line": 853,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 847,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 847,
+ "start_region_line": 846
+ },
+ {
+ "end_outermost_loop": 848,
+ "end_region_line": 853,
+ "line": " return 0\n",
+ "lineno": 848,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 848,
+ "start_region_line": 846
+ },
+ {
+ "end_outermost_loop": 851,
+ "end_region_line": 853,
+ "line": " with self.pt_lock:\n",
+ "lineno": 849,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 849,
+ "start_region_line": 846
+ },
+ {
+ "end_outermost_loop": 851,
+ "end_region_line": 853,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 850,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 850,
+ "start_region_line": 846
+ },
+ {
+ "end_outermost_loop": 851,
+ "end_region_line": 853,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_TEMPERATURE_LIMIT)\n",
+ "lineno": 851,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 851,
+ "start_region_line": 846
+ },
+ {
+ "end_outermost_loop": 852,
+ "end_region_line": 853,
+ "line": " self.handle_comm_result('XL430_ADDR_TEMPERATURE_LIMIT', dxl_comm_result, dxl_error)\n",
+ "lineno": 852,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 852,
+ "start_region_line": 846
+ },
+ {
+ "end_outermost_loop": 853,
+ "end_region_line": 853,
+ "line": " return p\n",
+ "lineno": 853,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 853,
+ "start_region_line": 846
+ },
+ {
+ "end_outermost_loop": 854,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 854,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 854,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 861,
+ "end_region_line": 861,
+ "line": " def set_temperature_limit(self,x):\n",
+ "lineno": 855,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 855,
+ "start_region_line": 855
+ },
+ {
+ "end_outermost_loop": 857,
+ "end_region_line": 861,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 856,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 856,
+ "start_region_line": 855
+ },
+ {
+ "end_outermost_loop": 857,
+ "end_region_line": 861,
+ "line": " return\n",
+ "lineno": 857,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 857,
+ "start_region_line": 855
+ },
+ {
+ "end_outermost_loop": 860,
+ "end_region_line": 861,
+ "line": " with self.pt_lock:\n",
+ "lineno": 858,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 858,
+ "start_region_line": 855
+ },
+ {
+ "end_outermost_loop": 860,
+ "end_region_line": 861,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 859,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 859,
+ "start_region_line": 855
+ },
+ {
+ "end_outermost_loop": 860,
+ "end_region_line": 861,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_TEMPERATURE_LIMIT, int(x))\n",
+ "lineno": 860,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 860,
+ "start_region_line": 855
+ },
+ {
+ "end_outermost_loop": 861,
+ "end_region_line": 861,
+ "line": " self.handle_comm_result('XL430_ADDR_TEMPERATURE_LIMIT', dxl_comm_result, dxl_error)\n",
+ "lineno": 861,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 861,
+ "start_region_line": 855
+ },
+ {
+ "end_outermost_loop": 862,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 862,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 862,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 870,
+ "end_region_line": 870,
+ "line": " def get_max_voltage_limit(self):\n",
+ "lineno": 863,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 863,
+ "start_region_line": 863
+ },
+ {
+ "end_outermost_loop": 865,
+ "end_region_line": 870,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 864,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 864,
+ "start_region_line": 863
+ },
+ {
+ "end_outermost_loop": 865,
+ "end_region_line": 870,
+ "line": " return 0\n",
+ "lineno": 865,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 865,
+ "start_region_line": 863
+ },
+ {
+ "end_outermost_loop": 868,
+ "end_region_line": 870,
+ "line": " with self.pt_lock:\n",
+ "lineno": 866,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 866,
+ "start_region_line": 863
+ },
+ {
+ "end_outermost_loop": 868,
+ "end_region_line": 870,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 867,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 867,
+ "start_region_line": 863
+ },
+ {
+ "end_outermost_loop": 868,
+ "end_region_line": 870,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read2ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_MAX_VOLTAGE_LIMIT)\n",
+ "lineno": 868,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 868,
+ "start_region_line": 863
+ },
+ {
+ "end_outermost_loop": 869,
+ "end_region_line": 870,
+ "line": " self.handle_comm_result('XL430_ADDR_MAX_VOLTAGE_LIMIT', dxl_comm_result, dxl_error)\n",
+ "lineno": 869,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 869,
+ "start_region_line": 863
+ },
+ {
+ "end_outermost_loop": 870,
+ "end_region_line": 870,
+ "line": " return p\n",
+ "lineno": 870,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 870,
+ "start_region_line": 863
+ },
+ {
+ "end_outermost_loop": 871,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 871,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 871,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 878,
+ "end_region_line": 878,
+ "line": " def set_max_voltage_limit(self,x):\n",
+ "lineno": 872,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 872,
+ "start_region_line": 872
+ },
+ {
+ "end_outermost_loop": 874,
+ "end_region_line": 878,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 873,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 873,
+ "start_region_line": 872
+ },
+ {
+ "end_outermost_loop": 874,
+ "end_region_line": 878,
+ "line": " return\n",
+ "lineno": 874,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 874,
+ "start_region_line": 872
+ },
+ {
+ "end_outermost_loop": 877,
+ "end_region_line": 878,
+ "line": " with self.pt_lock:\n",
+ "lineno": 875,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 875,
+ "start_region_line": 872
+ },
+ {
+ "end_outermost_loop": 877,
+ "end_region_line": 878,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 876,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 876,
+ "start_region_line": 872
+ },
+ {
+ "end_outermost_loop": 877,
+ "end_region_line": 878,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write2ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_MAX_VOLTAGE_LIMIT, int(x))\n",
+ "lineno": 877,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 877,
+ "start_region_line": 872
+ },
+ {
+ "end_outermost_loop": 878,
+ "end_region_line": 878,
+ "line": " self.handle_comm_result('XL430_ADDR_MAX_VOLTAGE_LIMIT', dxl_comm_result, dxl_error)\n",
+ "lineno": 878,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 878,
+ "start_region_line": 872
+ },
+ {
+ "end_outermost_loop": 879,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 879,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 879,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 887,
+ "end_region_line": 887,
+ "line": " def get_min_voltage_limit(self):\n",
+ "lineno": 880,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 880,
+ "start_region_line": 880
+ },
+ {
+ "end_outermost_loop": 882,
+ "end_region_line": 887,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 881,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 881,
+ "start_region_line": 880
+ },
+ {
+ "end_outermost_loop": 882,
+ "end_region_line": 887,
+ "line": " return 0\n",
+ "lineno": 882,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 882,
+ "start_region_line": 880
+ },
+ {
+ "end_outermost_loop": 885,
+ "end_region_line": 887,
+ "line": " with self.pt_lock:\n",
+ "lineno": 883,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 883,
+ "start_region_line": 880
+ },
+ {
+ "end_outermost_loop": 885,
+ "end_region_line": 887,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 884,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 884,
+ "start_region_line": 880
+ },
+ {
+ "end_outermost_loop": 885,
+ "end_region_line": 887,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read2ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_MIN_VOLTAGE_LIMIT)\n",
+ "lineno": 885,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 885,
+ "start_region_line": 880
+ },
+ {
+ "end_outermost_loop": 886,
+ "end_region_line": 887,
+ "line": " self.handle_comm_result('XL430_ADDR_MIN_VOLTAGE_LIMIT', dxl_comm_result, dxl_error)\n",
+ "lineno": 886,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 886,
+ "start_region_line": 880
+ },
+ {
+ "end_outermost_loop": 887,
+ "end_region_line": 887,
+ "line": " return p\n",
+ "lineno": 887,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 887,
+ "start_region_line": 880
+ },
+ {
+ "end_outermost_loop": 888,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 888,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 888,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 895,
+ "end_region_line": 895,
+ "line": " def set_min_voltage_limit(self,x):\n",
+ "lineno": 889,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 889,
+ "start_region_line": 889
+ },
+ {
+ "end_outermost_loop": 891,
+ "end_region_line": 895,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 890,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 890,
+ "start_region_line": 889
+ },
+ {
+ "end_outermost_loop": 891,
+ "end_region_line": 895,
+ "line": " return\n",
+ "lineno": 891,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 891,
+ "start_region_line": 889
+ },
+ {
+ "end_outermost_loop": 894,
+ "end_region_line": 895,
+ "line": " with self.pt_lock:\n",
+ "lineno": 892,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 892,
+ "start_region_line": 889
+ },
+ {
+ "end_outermost_loop": 894,
+ "end_region_line": 895,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 893,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 893,
+ "start_region_line": 889
+ },
+ {
+ "end_outermost_loop": 894,
+ "end_region_line": 895,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write2ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_MIN_VOLTAGE_LIMIT, int(x))\n",
+ "lineno": 894,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 894,
+ "start_region_line": 889
+ },
+ {
+ "end_outermost_loop": 895,
+ "end_region_line": 895,
+ "line": " self.handle_comm_result('XL430_ADDR_MIN_VOLTAGE_LIMIT', dxl_comm_result, dxl_error)\n",
+ "lineno": 895,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 895,
+ "start_region_line": 889
+ },
+ {
+ "end_outermost_loop": 896,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 896,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 896,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 904,
+ "end_region_line": 904,
+ "line": " def get_vel_limit(self):\n",
+ "lineno": 897,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 897,
+ "start_region_line": 897
+ },
+ {
+ "end_outermost_loop": 899,
+ "end_region_line": 904,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 898,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 898,
+ "start_region_line": 897
+ },
+ {
+ "end_outermost_loop": 899,
+ "end_region_line": 904,
+ "line": " return 0\n",
+ "lineno": 899,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 899,
+ "start_region_line": 897
+ },
+ {
+ "end_outermost_loop": 902,
+ "end_region_line": 904,
+ "line": " with self.pt_lock:\n",
+ "lineno": 900,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 900,
+ "start_region_line": 897
+ },
+ {
+ "end_outermost_loop": 902,
+ "end_region_line": 904,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 901,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 901,
+ "start_region_line": 897
+ },
+ {
+ "end_outermost_loop": 902,
+ "end_region_line": 904,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read4ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_VELOCITY_LIMIT)\n",
+ "lineno": 902,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 902,
+ "start_region_line": 897
+ },
+ {
+ "end_outermost_loop": 903,
+ "end_region_line": 904,
+ "line": " self.handle_comm_result('XL430_ADDR_VELOCITY_LIMIT', dxl_comm_result, dxl_error)\n",
+ "lineno": 903,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 903,
+ "start_region_line": 897
+ },
+ {
+ "end_outermost_loop": 904,
+ "end_region_line": 904,
+ "line": " return p\n",
+ "lineno": 904,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 904,
+ "start_region_line": 897
+ },
+ {
+ "end_outermost_loop": 905,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 905,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 905,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 912,
+ "end_region_line": 912,
+ "line": " def set_vel_limit(self,x):\n",
+ "lineno": 906,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 906,
+ "start_region_line": 906
+ },
+ {
+ "end_outermost_loop": 908,
+ "end_region_line": 912,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 907,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 907,
+ "start_region_line": 906
+ },
+ {
+ "end_outermost_loop": 908,
+ "end_region_line": 912,
+ "line": " return\n",
+ "lineno": 908,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 908,
+ "start_region_line": 906
+ },
+ {
+ "end_outermost_loop": 911,
+ "end_region_line": 912,
+ "line": " with self.pt_lock:\n",
+ "lineno": 909,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 909,
+ "start_region_line": 906
+ },
+ {
+ "end_outermost_loop": 911,
+ "end_region_line": 912,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 910,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 910,
+ "start_region_line": 906
+ },
+ {
+ "end_outermost_loop": 911,
+ "end_region_line": 912,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write4ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_VELOCITY_LIMIT, int(x))\n",
+ "lineno": 911,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 911,
+ "start_region_line": 906
+ },
+ {
+ "end_outermost_loop": 912,
+ "end_region_line": 912,
+ "line": " self.handle_comm_result('XL430_ADDR_VELOCITY_LIMIT', dxl_comm_result, dxl_error)\n",
+ "lineno": 912,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 912,
+ "start_region_line": 906
+ },
+ {
+ "end_outermost_loop": 913,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 913,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 913,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 921,
+ "end_region_line": 921,
+ "line": " def get_max_pos_limit(self):\n",
+ "lineno": 914,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 914,
+ "start_region_line": 914
+ },
+ {
+ "end_outermost_loop": 916,
+ "end_region_line": 921,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 915,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 915,
+ "start_region_line": 914
+ },
+ {
+ "end_outermost_loop": 916,
+ "end_region_line": 921,
+ "line": " return 0\n",
+ "lineno": 916,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 916,
+ "start_region_line": 914
+ },
+ {
+ "end_outermost_loop": 919,
+ "end_region_line": 921,
+ "line": " with self.pt_lock:\n",
+ "lineno": 917,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 917,
+ "start_region_line": 914
+ },
+ {
+ "end_outermost_loop": 919,
+ "end_region_line": 921,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 918,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 918,
+ "start_region_line": 914
+ },
+ {
+ "end_outermost_loop": 919,
+ "end_region_line": 921,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read4ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_MAX_POS_LIMIT)\n",
+ "lineno": 919,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 919,
+ "start_region_line": 914
+ },
+ {
+ "end_outermost_loop": 920,
+ "end_region_line": 921,
+ "line": " self.handle_comm_result('XL430_ADDR_MAX_POS_LIMIT', dxl_comm_result, dxl_error)\n",
+ "lineno": 920,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 920,
+ "start_region_line": 914
+ },
+ {
+ "end_outermost_loop": 921,
+ "end_region_line": 921,
+ "line": " return p\n",
+ "lineno": 921,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 921,
+ "start_region_line": 914
+ },
+ {
+ "end_outermost_loop": 922,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 922,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 922,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 929,
+ "end_region_line": 929,
+ "line": " def set_max_pos_limit(self,x):\n",
+ "lineno": 923,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 923,
+ "start_region_line": 923
+ },
+ {
+ "end_outermost_loop": 925,
+ "end_region_line": 929,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 924,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 924,
+ "start_region_line": 923
+ },
+ {
+ "end_outermost_loop": 925,
+ "end_region_line": 929,
+ "line": " return\n",
+ "lineno": 925,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 925,
+ "start_region_line": 923
+ },
+ {
+ "end_outermost_loop": 928,
+ "end_region_line": 929,
+ "line": " with self.pt_lock:\n",
+ "lineno": 926,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 926,
+ "start_region_line": 923
+ },
+ {
+ "end_outermost_loop": 928,
+ "end_region_line": 929,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 927,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 927,
+ "start_region_line": 923
+ },
+ {
+ "end_outermost_loop": 928,
+ "end_region_line": 929,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write4ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_MAX_POS_LIMIT, int(x))\n",
+ "lineno": 928,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 928,
+ "start_region_line": 923
+ },
+ {
+ "end_outermost_loop": 929,
+ "end_region_line": 929,
+ "line": " self.handle_comm_result('XL430_ADDR_MAX_POS_LIMIT', dxl_comm_result, dxl_error)\n",
+ "lineno": 929,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 929,
+ "start_region_line": 923
+ },
+ {
+ "end_outermost_loop": 930,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 930,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 930,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 937,
+ "end_region_line": 937,
+ "line": " def set_min_pos_limit(self,x):\n",
+ "lineno": 931,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 931,
+ "start_region_line": 931
+ },
+ {
+ "end_outermost_loop": 933,
+ "end_region_line": 937,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 932,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 932,
+ "start_region_line": 931
+ },
+ {
+ "end_outermost_loop": 933,
+ "end_region_line": 937,
+ "line": " return\n",
+ "lineno": 933,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 933,
+ "start_region_line": 931
+ },
+ {
+ "end_outermost_loop": 936,
+ "end_region_line": 937,
+ "line": " with self.pt_lock:\n",
+ "lineno": 934,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 934,
+ "start_region_line": 931
+ },
+ {
+ "end_outermost_loop": 936,
+ "end_region_line": 937,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 935,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 935,
+ "start_region_line": 931
+ },
+ {
+ "end_outermost_loop": 936,
+ "end_region_line": 937,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write4ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_MIN_POS_LIMIT, int(x))\n",
+ "lineno": 936,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 936,
+ "start_region_line": 931
+ },
+ {
+ "end_outermost_loop": 937,
+ "end_region_line": 937,
+ "line": " self.handle_comm_result('XL430_ADDR_MIN_POS_LIMIT', dxl_comm_result, dxl_error)\n",
+ "lineno": 937,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 937,
+ "start_region_line": 931
+ },
+ {
+ "end_outermost_loop": 938,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 938,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 938,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 946,
+ "end_region_line": 946,
+ "line": " def get_min_pos_limit(self):\n",
+ "lineno": 939,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 939,
+ "start_region_line": 939
+ },
+ {
+ "end_outermost_loop": 941,
+ "end_region_line": 946,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 940,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 940,
+ "start_region_line": 939
+ },
+ {
+ "end_outermost_loop": 941,
+ "end_region_line": 946,
+ "line": " return 0\n",
+ "lineno": 941,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 941,
+ "start_region_line": 939
+ },
+ {
+ "end_outermost_loop": 944,
+ "end_region_line": 946,
+ "line": " with self.pt_lock:\n",
+ "lineno": 942,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 942,
+ "start_region_line": 939
+ },
+ {
+ "end_outermost_loop": 944,
+ "end_region_line": 946,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 943,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 943,
+ "start_region_line": 939
+ },
+ {
+ "end_outermost_loop": 944,
+ "end_region_line": 946,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read4ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_MIN_POS_LIMIT)\n",
+ "lineno": 944,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 944,
+ "start_region_line": 939
+ },
+ {
+ "end_outermost_loop": 945,
+ "end_region_line": 946,
+ "line": " self.handle_comm_result('XL430_ADDR_MIN_POS_LIMIT', dxl_comm_result, dxl_error)\n",
+ "lineno": 945,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 945,
+ "start_region_line": 939
+ },
+ {
+ "end_outermost_loop": 946,
+ "end_region_line": 946,
+ "line": " return p\n",
+ "lineno": 946,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 946,
+ "start_region_line": 939
+ },
+ {
+ "end_outermost_loop": 947,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 947,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 947,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 955,
+ "end_region_line": 955,
+ "line": " def get_temp(self):\n",
+ "lineno": 948,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 948,
+ "start_region_line": 948
+ },
+ {
+ "end_outermost_loop": 950,
+ "end_region_line": 955,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 949,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 949,
+ "start_region_line": 948
+ },
+ {
+ "end_outermost_loop": 950,
+ "end_region_line": 955,
+ "line": " return 0\n",
+ "lineno": 950,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 950,
+ "start_region_line": 948
+ },
+ {
+ "end_outermost_loop": 953,
+ "end_region_line": 955,
+ "line": " with self.pt_lock:\n",
+ "lineno": 951,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 951,
+ "start_region_line": 948
+ },
+ {
+ "end_outermost_loop": 953,
+ "end_region_line": 955,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 952,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 952,
+ "start_region_line": 948
+ },
+ {
+ "end_outermost_loop": 953,
+ "end_region_line": 955,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_PRESENT_TEMPERATURE)\n",
+ "lineno": 953,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 35.313443581647,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 953,
+ "start_region_line": 948
+ },
+ {
+ "end_outermost_loop": 954,
+ "end_region_line": 955,
+ "line": " self.handle_comm_result('XL430_ADDR_PRESENT_TEMPERATURE', dxl_comm_result, dxl_error)\n",
+ "lineno": 954,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 954,
+ "start_region_line": 948
+ },
+ {
+ "end_outermost_loop": 955,
+ "end_region_line": 955,
+ "line": " return p\n",
+ "lineno": 955,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 955,
+ "start_region_line": 948
+ },
+ {
+ "end_outermost_loop": 956,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 956,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 956,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 963,
+ "end_region_line": 963,
+ "line": " def set_moving_threshold(self,x): #unit of 0.229 rev/min, default 10\n",
+ "lineno": 957,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 957,
+ "start_region_line": 957
+ },
+ {
+ "end_outermost_loop": 959,
+ "end_region_line": 963,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 958,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 958,
+ "start_region_line": 957
+ },
+ {
+ "end_outermost_loop": 959,
+ "end_region_line": 963,
+ "line": " return\n",
+ "lineno": 959,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 959,
+ "start_region_line": 957
+ },
+ {
+ "end_outermost_loop": 962,
+ "end_region_line": 963,
+ "line": " with self.pt_lock:\n",
+ "lineno": 960,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 960,
+ "start_region_line": 957
+ },
+ {
+ "end_outermost_loop": 962,
+ "end_region_line": 963,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 961,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 961,
+ "start_region_line": 957
+ },
+ {
+ "end_outermost_loop": 962,
+ "end_region_line": 963,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write4ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_MOVING_THRESHOLD, int(x))\n",
+ "lineno": 962,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 962,
+ "start_region_line": 957
+ },
+ {
+ "end_outermost_loop": 963,
+ "end_region_line": 963,
+ "line": " self.handle_comm_result('XL430_ADDR_MOVING_THRESHOLD', dxl_comm_result, dxl_error)\n",
+ "lineno": 963,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 963,
+ "start_region_line": 957
+ },
+ {
+ "end_outermost_loop": 964,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 964,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 964,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 973,
+ "end_region_line": 973,
+ "line": " def get_moving_threshold(self):\n",
+ "lineno": 965,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 965,
+ "start_region_line": 965
+ },
+ {
+ "end_outermost_loop": 967,
+ "end_region_line": 973,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 966,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 966,
+ "start_region_line": 965
+ },
+ {
+ "end_outermost_loop": 967,
+ "end_region_line": 973,
+ "line": " return 0\n",
+ "lineno": 967,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 967,
+ "start_region_line": 965
+ },
+ {
+ "end_outermost_loop": 971,
+ "end_region_line": 973,
+ "line": " with self.pt_lock:\n",
+ "lineno": 968,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 968,
+ "start_region_line": 965
+ },
+ {
+ "end_outermost_loop": 971,
+ "end_region_line": 973,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 969,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 969,
+ "start_region_line": 965
+ },
+ {
+ "end_outermost_loop": 970,
+ "end_region_line": 973,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read4ByteTxRx(self.port_handler, self.dxl_id,\n",
+ "lineno": 970,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 970,
+ "start_region_line": 965
+ },
+ {
+ "end_outermost_loop": 971,
+ "end_region_line": 973,
+ "line": " XL430_ADDR_MOVING_THRESHOLD)\n",
+ "lineno": 971,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 971,
+ "start_region_line": 965
+ },
+ {
+ "end_outermost_loop": 972,
+ "end_region_line": 973,
+ "line": " self.handle_comm_result('XL430_ADDR_MOVING_THRESHOLD', dxl_comm_result, dxl_error)\n",
+ "lineno": 972,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 972,
+ "start_region_line": 965
+ },
+ {
+ "end_outermost_loop": 973,
+ "end_region_line": 973,
+ "line": " return p\n",
+ "lineno": 973,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 973,
+ "start_region_line": 965
+ },
+ {
+ "end_outermost_loop": 974,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 974,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 974,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 981,
+ "end_region_line": 981,
+ "line": " def set_pwm_limit(self,x): #0(0%) ~ 885(100%\n",
+ "lineno": 975,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 975,
+ "start_region_line": 975
+ },
+ {
+ "end_outermost_loop": 977,
+ "end_region_line": 981,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 976,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 976,
+ "start_region_line": 975
+ },
+ {
+ "end_outermost_loop": 977,
+ "end_region_line": 981,
+ "line": " return\n",
+ "lineno": 977,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 977,
+ "start_region_line": 975
+ },
+ {
+ "end_outermost_loop": 980,
+ "end_region_line": 981,
+ "line": " with self.pt_lock:\n",
+ "lineno": 978,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 978,
+ "start_region_line": 975
+ },
+ {
+ "end_outermost_loop": 980,
+ "end_region_line": 981,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 979,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 979,
+ "start_region_line": 975
+ },
+ {
+ "end_outermost_loop": 980,
+ "end_region_line": 981,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write2ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_PWM_LIMIT, int(x))\n",
+ "lineno": 980,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 980,
+ "start_region_line": 975
+ },
+ {
+ "end_outermost_loop": 981,
+ "end_region_line": 981,
+ "line": " self.handle_comm_result('XL430_ADDR_PWM_LIMIT', dxl_comm_result, dxl_error)\n",
+ "lineno": 981,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 981,
+ "start_region_line": 975
+ },
+ {
+ "end_outermost_loop": 982,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 982,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 982,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 990,
+ "end_region_line": 990,
+ "line": " def get_pwm_limit(self):\n",
+ "lineno": 983,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 983,
+ "start_region_line": 983
+ },
+ {
+ "end_outermost_loop": 985,
+ "end_region_line": 990,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 984,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 984,
+ "start_region_line": 983
+ },
+ {
+ "end_outermost_loop": 985,
+ "end_region_line": 990,
+ "line": " return 0\n",
+ "lineno": 985,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 985,
+ "start_region_line": 983
+ },
+ {
+ "end_outermost_loop": 988,
+ "end_region_line": 990,
+ "line": " with self.pt_lock:\n",
+ "lineno": 986,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 986,
+ "start_region_line": 983
+ },
+ {
+ "end_outermost_loop": 988,
+ "end_region_line": 990,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 987,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 987,
+ "start_region_line": 983
+ },
+ {
+ "end_outermost_loop": 988,
+ "end_region_line": 990,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read2ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_PWM_LIMIT)\n",
+ "lineno": 988,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 988,
+ "start_region_line": 983
+ },
+ {
+ "end_outermost_loop": 989,
+ "end_region_line": 990,
+ "line": " self.handle_comm_result('XL430_ADDR_PWM_LIMIT', dxl_comm_result, dxl_error)\n",
+ "lineno": 989,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 989,
+ "start_region_line": 983
+ },
+ {
+ "end_outermost_loop": 990,
+ "end_region_line": 990,
+ "line": " return p\n",
+ "lineno": 990,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 990,
+ "start_region_line": 983
+ },
+ {
+ "end_outermost_loop": 991,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 991,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 991,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 999,
+ "end_region_line": 999,
+ "line": " def is_moving(self):\n",
+ "lineno": 992,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 992,
+ "start_region_line": 992
+ },
+ {
+ "end_outermost_loop": 994,
+ "end_region_line": 999,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 993,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 993,
+ "start_region_line": 992
+ },
+ {
+ "end_outermost_loop": 994,
+ "end_region_line": 999,
+ "line": " return 0\n",
+ "lineno": 994,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 994,
+ "start_region_line": 992
+ },
+ {
+ "end_outermost_loop": 997,
+ "end_region_line": 999,
+ "line": " with self.pt_lock:\n",
+ "lineno": 995,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 995,
+ "start_region_line": 992
+ },
+ {
+ "end_outermost_loop": 997,
+ "end_region_line": 999,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 996,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 996,
+ "start_region_line": 992
+ },
+ {
+ "end_outermost_loop": 997,
+ "end_region_line": 999,
+ "line": " p, dxl_comm_result, dxl_error = self.packet_handler.read1ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_MOVING)\n",
+ "lineno": 997,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 997,
+ "start_region_line": 992
+ },
+ {
+ "end_outermost_loop": 998,
+ "end_region_line": 999,
+ "line": " self.handle_comm_result('XL430_ADDR_MOVING', dxl_comm_result, dxl_error)\n",
+ "lineno": 998,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 998,
+ "start_region_line": 992
+ },
+ {
+ "end_outermost_loop": 999,
+ "end_region_line": 999,
+ "line": " return p\n",
+ "lineno": 999,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 999,
+ "start_region_line": 992
+ },
+ {
+ "end_outermost_loop": 1000,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 1000,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1000,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 1018,
+ "end_region_line": 1018,
+ "line": " def zero_position(self,verbose=False):\n",
+ "lineno": 1001,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1001,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1003,
+ "end_region_line": 1018,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 1002,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1002,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1003,
+ "end_region_line": 1018,
+ "line": " return\n",
+ "lineno": 1003,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1003,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1004,
+ "end_region_line": 1018,
+ "line": " self.logger.debug('Previous HOMING_OFFSET in EEPROM {0}'.format(self.get_homing_offset()))\n",
+ "lineno": 1004,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1004,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1006,
+ "end_region_line": 1018,
+ "line": " if verbose:\n",
+ "lineno": 1005,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1005,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1006,
+ "end_region_line": 1018,
+ "line": " print('Previous HOMING_OFFSET in EEPROM', self.get_homing_offset())\n",
+ "lineno": 1006,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1006,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1007,
+ "end_region_line": 1018,
+ "line": " self.set_homing_offset(0)\n",
+ "lineno": 1007,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1007,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1008,
+ "end_region_line": 1018,
+ "line": " h=-1*self.get_pos()\n",
+ "lineno": 1008,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1008,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1009,
+ "end_region_line": 1018,
+ "line": " self.logger.debug('Setting homing offset to {0}'.format(h))\n",
+ "lineno": 1009,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1009,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1011,
+ "end_region_line": 1018,
+ "line": " if verbose:\n",
+ "lineno": 1010,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1010,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1011,
+ "end_region_line": 1018,
+ "line": " print('Setting homing offset to',h)\n",
+ "lineno": 1011,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1011,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1012,
+ "end_region_line": 1018,
+ "line": " self.set_homing_offset(h)\n",
+ "lineno": 1012,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1012,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1013,
+ "end_region_line": 1018,
+ "line": " self.logger.debug('New HOMING_OFFSET in EEPROM {0}'.format(self.get_homing_offset()))\n",
+ "lineno": 1013,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1013,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1014,
+ "end_region_line": 1018,
+ "line": " self.logger.debug('Current position after homing {0}'.format(self.get_pos()))\n",
+ "lineno": 1014,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1014,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1017,
+ "end_region_line": 1018,
+ "line": " if verbose:\n",
+ "lineno": 1015,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1015,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1016,
+ "end_region_line": 1018,
+ "line": " print('New HOMING_OFFSET in EEPROM', self.get_homing_offset())\n",
+ "lineno": 1016,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1016,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1017,
+ "end_region_line": 1018,
+ "line": " print('Current position after homing',self.get_pos())\n",
+ "lineno": 1017,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1017,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1018,
+ "end_region_line": 1018,
+ "line": " return\n",
+ "lineno": 1018,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1018,
+ "start_region_line": 1001
+ },
+ {
+ "end_outermost_loop": 1019,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 1019,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1019,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 1027,
+ "end_region_line": 1027,
+ "line": " def get_homing_offset(self):\n",
+ "lineno": 1020,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1020,
+ "start_region_line": 1020
+ },
+ {
+ "end_outermost_loop": 1022,
+ "end_region_line": 1027,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 1021,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1021,
+ "start_region_line": 1020
+ },
+ {
+ "end_outermost_loop": 1022,
+ "end_region_line": 1027,
+ "line": " return 0\n",
+ "lineno": 1022,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1022,
+ "start_region_line": 1020
+ },
+ {
+ "end_outermost_loop": 1025,
+ "end_region_line": 1027,
+ "line": " with self.pt_lock:\n",
+ "lineno": 1023,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1023,
+ "start_region_line": 1020
+ },
+ {
+ "end_outermost_loop": 1025,
+ "end_region_line": 1027,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 1024,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1024,
+ "start_region_line": 1020
+ },
+ {
+ "end_outermost_loop": 1025,
+ "end_region_line": 1027,
+ "line": " xn, dxl_comm_result, dxl_error = self.read_int32_t(XL430_ADDR_HOMING_OFFSET)\n",
+ "lineno": 1025,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1025,
+ "start_region_line": 1020
+ },
+ {
+ "end_outermost_loop": 1026,
+ "end_region_line": 1027,
+ "line": " self.handle_comm_result('XL430_ADDR_HOMING_OFFSET', dxl_comm_result, dxl_error)\n",
+ "lineno": 1026,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1026,
+ "start_region_line": 1020
+ },
+ {
+ "end_outermost_loop": 1027,
+ "end_region_line": 1027,
+ "line": " return xn\n",
+ "lineno": 1027,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1027,
+ "start_region_line": 1020
+ },
+ {
+ "end_outermost_loop": 1028,
+ "end_region_line": 1035,
+ "line": "\n",
+ "lineno": 1028,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1028,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 1035,
+ "end_region_line": 1035,
+ "line": " def set_homing_offset(self,x):\n",
+ "lineno": 1029,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1029,
+ "start_region_line": 1029
+ },
+ {
+ "end_outermost_loop": 1031,
+ "end_region_line": 1035,
+ "line": " if not self.hw_valid:\n",
+ "lineno": 1030,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1030,
+ "start_region_line": 1029
+ },
+ {
+ "end_outermost_loop": 1031,
+ "end_region_line": 1035,
+ "line": " return\n",
+ "lineno": 1031,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1031,
+ "start_region_line": 1029
+ },
+ {
+ "end_outermost_loop": 1034,
+ "end_region_line": 1035,
+ "line": " with self.pt_lock:\n",
+ "lineno": 1032,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1032,
+ "start_region_line": 1029
+ },
+ {
+ "end_outermost_loop": 1034,
+ "end_region_line": 1035,
+ "line": " with DelayedKeyboardInterrupt():\n",
+ "lineno": 1033,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1033,
+ "start_region_line": 1029
+ },
+ {
+ "end_outermost_loop": 1034,
+ "end_region_line": 1035,
+ "line": " dxl_comm_result, dxl_error = self.packet_handler.write4ByteTxRx(self.port_handler, self.dxl_id, XL430_ADDR_HOMING_OFFSET, int(x))\n",
+ "lineno": 1034,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1034,
+ "start_region_line": 1029
+ },
+ {
+ "end_outermost_loop": 1035,
+ "end_region_line": 1035,
+ "line": " self.handle_comm_result('XL430_ADDR_HOMING_OFFSET', dxl_comm_result, dxl_error)\n",
+ "lineno": 1035,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1035,
+ "start_region_line": 1029
+ }
+ ],
+ "percent_cpu_time": 0.0
+ },
+ "/home/hello-robot/repos/stretch_body/body/stretch_body/hello_utils.py": {
+ "functions": [],
+ "imports": [
+ "from __future__ import print_function",
+ "import yaml",
+ "import math",
+ "import os",
+ "import time",
+ "import numpy as np",
+ "import sys",
+ "import numbers",
+ "import subprocess",
+ "import pyrealsense2 as rs",
+ "import cv2",
+ "import matplotlib.pyplot as plt"
+ ],
+ "leaks": {},
+ "lines": [
+ {
+ "end_outermost_loop": 1,
+ "end_region_line": 1,
+ "line": "from __future__ import print_function\n",
+ "lineno": 1,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1,
+ "start_region_line": 1
+ },
+ {
+ "end_outermost_loop": 2,
+ "end_region_line": 2,
+ "line": "import yaml\n",
+ "lineno": 2,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 2,
+ "start_region_line": 2
+ },
+ {
+ "end_outermost_loop": 3,
+ "end_region_line": 3,
+ "line": "import math\n",
+ "lineno": 3,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 3,
+ "start_region_line": 3
+ },
+ {
+ "end_outermost_loop": 4,
+ "end_region_line": 4,
+ "line": "import os\n",
+ "lineno": 4,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 4,
+ "start_region_line": 4
+ },
+ {
+ "end_outermost_loop": 5,
+ "end_region_line": 5,
+ "line": "import time\n",
+ "lineno": 5,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 5,
+ "start_region_line": 5
+ },
+ {
+ "end_outermost_loop": 6,
+ "end_region_line": 6,
+ "line": "import logging\n",
+ "lineno": 6,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 6,
+ "start_region_line": 6
+ },
+ {
+ "end_outermost_loop": 7,
+ "end_region_line": 7,
+ "line": "import numpy as np\n",
+ "lineno": 7,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 133.60260659274087,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 7,
+ "start_region_line": 7
+ },
+ {
+ "end_outermost_loop": 8,
+ "end_region_line": 8,
+ "line": "import sys\n",
+ "lineno": 8,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 8,
+ "start_region_line": 8
+ },
+ {
+ "end_outermost_loop": 9,
+ "end_region_line": 9,
+ "line": "import numbers\n",
+ "lineno": 9,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 9,
+ "start_region_line": 9
+ },
+ {
+ "end_outermost_loop": 10,
+ "end_region_line": 10,
+ "line": "import subprocess\n",
+ "lineno": 10,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 10,
+ "start_region_line": 10
+ },
+ {
+ "end_outermost_loop": 11,
+ "end_region_line": 11,
+ "line": "import pyrealsense2 as rs\n",
+ "lineno": 11,
+ "memory_samples": [
+ [
+ 657391915,
+ 10.034314155578613
+ ]
+ ],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 10.034314155578613,
+ "n_malloc_mb": 10.034314155578613,
+ "n_mallocs": 0,
+ "n_peak_mb": 10.034314155578613,
+ "n_python_fraction": 0.9965480000000001,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.20053696514043517,
+ "start_outermost_loop": 11,
+ "start_region_line": 11
+ },
+ {
+ "end_outermost_loop": 12,
+ "end_region_line": 12,
+ "line": "import cv2\n",
+ "lineno": 12,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 17.629472728812654,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 12,
+ "start_region_line": 12
+ },
+ {
+ "end_outermost_loop": 13,
+ "end_region_line": 13,
+ "line": "\n",
+ "lineno": 13,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 13,
+ "start_region_line": 13
+ },
+ {
+ "end_outermost_loop": 16,
+ "end_region_line": 16,
+ "line": "def print_stretch_re_use():\n",
+ "lineno": 14,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 14,
+ "start_region_line": 14
+ },
+ {
+ "end_outermost_loop": 15,
+ "end_region_line": 16,
+ "line": " print(\"For use with S T R E T C H (R) from Hello Robot Inc.\")\n",
+ "lineno": 15,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 15,
+ "start_region_line": 14
+ },
+ {
+ "end_outermost_loop": 16,
+ "end_region_line": 16,
+ "line": " print(\"---------------------------------------------------------------------\\n\")\n",
+ "lineno": 16,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 16,
+ "start_region_line": 14
+ },
+ {
+ "end_outermost_loop": 17,
+ "end_region_line": 17,
+ "line": "\n",
+ "lineno": 17,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 17,
+ "start_region_line": 17
+ },
+ {
+ "end_outermost_loop": 31,
+ "end_region_line": 31,
+ "line": "def create_time_string(time_format='%Y%m%d%H%M%S'):\n",
+ "lineno": 18,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 18,
+ "start_region_line": 18
+ },
+ {
+ "end_outermost_loop": 19,
+ "end_region_line": 31,
+ "line": " \"\"\"Returns current time formatted as `time_format`\n",
+ "lineno": 19,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 19,
+ "start_region_line": 18
+ },
+ {
+ "end_outermost_loop": 20,
+ "end_region_line": 31,
+ "line": "\n",
+ "lineno": 20,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 20,
+ "start_region_line": 18
+ },
+ {
+ "end_outermost_loop": 21,
+ "end_region_line": 31,
+ "line": " Parameters\n",
+ "lineno": 21,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 21,
+ "start_region_line": 18
+ },
+ {
+ "end_outermost_loop": 22,
+ "end_region_line": 31,
+ "line": " ----------\n",
+ "lineno": 22,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 22,
+ "start_region_line": 18
+ },
+ {
+ "end_outermost_loop": 23,
+ "end_region_line": 31,
+ "line": " time_format : str\n",
+ "lineno": 23,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 23,
+ "start_region_line": 18
+ },
+ {
+ "end_outermost_loop": 24,
+ "end_region_line": 31,
+ "line": " Refer https://docs.python.org/3/library/time.html#time.strftime for options\n",
+ "lineno": 24,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 24,
+ "start_region_line": 18
+ },
+ {
+ "end_outermost_loop": 25,
+ "end_region_line": 31,
+ "line": "\n",
+ "lineno": 25,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 25,
+ "start_region_line": 18
+ },
+ {
+ "end_outermost_loop": 26,
+ "end_region_line": 31,
+ "line": " Returns\n",
+ "lineno": 26,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 26,
+ "start_region_line": 18
+ },
+ {
+ "end_outermost_loop": 27,
+ "end_region_line": 31,
+ "line": " -------\n",
+ "lineno": 27,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 27,
+ "start_region_line": 18
+ },
+ {
+ "end_outermost_loop": 28,
+ "end_region_line": 31,
+ "line": " str\n",
+ "lineno": 28,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 28,
+ "start_region_line": 18
+ },
+ {
+ "end_outermost_loop": 29,
+ "end_region_line": 31,
+ "line": " time as string in requested format\n",
+ "lineno": 29,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 29,
+ "start_region_line": 18
+ },
+ {
+ "end_outermost_loop": 30,
+ "end_region_line": 31,
+ "line": " \"\"\"\n",
+ "lineno": 30,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 30,
+ "start_region_line": 18
+ },
+ {
+ "end_outermost_loop": 31,
+ "end_region_line": 31,
+ "line": " return time.strftime(time_format)\n",
+ "lineno": 31,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 31,
+ "start_region_line": 18
+ },
+ {
+ "end_outermost_loop": 32,
+ "end_region_line": 32,
+ "line": "\n",
+ "lineno": 32,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 32,
+ "start_region_line": 32
+ },
+ {
+ "end_outermost_loop": 34,
+ "end_region_line": 34,
+ "line": "def deg_to_rad(x):\n",
+ "lineno": 33,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 33,
+ "start_region_line": 33
+ },
+ {
+ "end_outermost_loop": 34,
+ "end_region_line": 34,
+ "line": " return math.pi*x/180.0\n",
+ "lineno": 34,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 34,
+ "start_region_line": 33
+ },
+ {
+ "end_outermost_loop": 35,
+ "end_region_line": 35,
+ "line": "\n",
+ "lineno": 35,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 35,
+ "start_region_line": 35
+ },
+ {
+ "end_outermost_loop": 37,
+ "end_region_line": 37,
+ "line": "def rad_to_deg(x):\n",
+ "lineno": 36,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 36,
+ "start_region_line": 36
+ },
+ {
+ "end_outermost_loop": 37,
+ "end_region_line": 37,
+ "line": " return 180.0*x/math.pi\n",
+ "lineno": 37,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 37,
+ "start_region_line": 36
+ },
+ {
+ "end_outermost_loop": 38,
+ "end_region_line": 38,
+ "line": "\n",
+ "lineno": 38,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 38,
+ "start_region_line": 38
+ },
+ {
+ "end_outermost_loop": 43,
+ "end_region_line": 43,
+ "line": "def confirm(question):\n",
+ "lineno": 39,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 39,
+ "start_region_line": 39
+ },
+ {
+ "end_outermost_loop": 40,
+ "end_region_line": 43,
+ "line": " reply = None\n",
+ "lineno": 40,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 40,
+ "start_region_line": 39
+ },
+ {
+ "end_outermost_loop": 42,
+ "end_region_line": 42,
+ "line": " while reply not in (\"y\", \"n\"):\n",
+ "lineno": 41,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 41,
+ "start_region_line": 41
+ },
+ {
+ "end_outermost_loop": 42,
+ "end_region_line": 42,
+ "line": " reply = input(question + \" (y/n)\").lower()\n",
+ "lineno": 42,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 41,
+ "start_region_line": 41
+ },
+ {
+ "end_outermost_loop": 43,
+ "end_region_line": 43,
+ "line": " return (reply == \"y\")\n",
+ "lineno": 43,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 43,
+ "start_region_line": 39
+ },
+ {
+ "end_outermost_loop": 44,
+ "end_region_line": 44,
+ "line": "\n",
+ "lineno": 44,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 44,
+ "start_region_line": 44
+ },
+ {
+ "end_outermost_loop": 45,
+ "end_region_line": 45,
+ "line": "\n",
+ "lineno": 45,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 45,
+ "start_region_line": 45
+ },
+ {
+ "end_outermost_loop": 47,
+ "end_region_line": 47,
+ "line": "def get_display():\n",
+ "lineno": 46,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 46,
+ "start_region_line": 46
+ },
+ {
+ "end_outermost_loop": 47,
+ "end_region_line": 47,
+ "line": " return os.environ.get('DISPLAY', None)\n",
+ "lineno": 47,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 47,
+ "start_region_line": 46
+ },
+ {
+ "end_outermost_loop": 48,
+ "end_region_line": 48,
+ "line": "\n",
+ "lineno": 48,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 48,
+ "start_region_line": 48
+ },
+ {
+ "end_outermost_loop": 50,
+ "end_region_line": 50,
+ "line": "def get_fleet_id():\n",
+ "lineno": 49,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 49,
+ "start_region_line": 49
+ },
+ {
+ "end_outermost_loop": 50,
+ "end_region_line": 50,
+ "line": " return os.environ['HELLO_FLEET_ID']\n",
+ "lineno": 50,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 50,
+ "start_region_line": 49
+ },
+ {
+ "end_outermost_loop": 51,
+ "end_region_line": 51,
+ "line": "\n",
+ "lineno": 51,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 51,
+ "start_region_line": 51
+ },
+ {
+ "end_outermost_loop": 53,
+ "end_region_line": 53,
+ "line": "def set_fleet_id(id):\n",
+ "lineno": 52,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 52,
+ "start_region_line": 52
+ },
+ {
+ "end_outermost_loop": 53,
+ "end_region_line": 53,
+ "line": " os.environ['HELLO_FLEET_ID']=id\n",
+ "lineno": 53,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 53,
+ "start_region_line": 52
+ },
+ {
+ "end_outermost_loop": 54,
+ "end_region_line": 54,
+ "line": "\n",
+ "lineno": 54,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 54,
+ "start_region_line": 54
+ },
+ {
+ "end_outermost_loop": 56,
+ "end_region_line": 56,
+ "line": "def get_fleet_directory():\n",
+ "lineno": 55,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 55,
+ "start_region_line": 55
+ },
+ {
+ "end_outermost_loop": 56,
+ "end_region_line": 56,
+ "line": " return os.environ['HELLO_FLEET_PATH']+'/'+get_fleet_id()+'/'\n",
+ "lineno": 56,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 56,
+ "start_region_line": 55
+ },
+ {
+ "end_outermost_loop": 57,
+ "end_region_line": 57,
+ "line": "\n",
+ "lineno": 57,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 57,
+ "start_region_line": 57
+ },
+ {
+ "end_outermost_loop": 58,
+ "end_region_line": 58,
+ "line": "\n",
+ "lineno": 58,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 58,
+ "start_region_line": 58
+ },
+ {
+ "end_outermost_loop": 61,
+ "end_region_line": 61,
+ "line": "def set_fleet_directory(fleet_path,fleet_id):\n",
+ "lineno": 59,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 59,
+ "start_region_line": 59
+ },
+ {
+ "end_outermost_loop": 60,
+ "end_region_line": 61,
+ "line": " os.environ['HELLO_FLEET_ID'] = fleet_id\n",
+ "lineno": 60,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 60,
+ "start_region_line": 59
+ },
+ {
+ "end_outermost_loop": 61,
+ "end_region_line": 61,
+ "line": " os.environ['HELLO_FLEET_PATH'] = fleet_path\n",
+ "lineno": 61,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 61,
+ "start_region_line": 59
+ },
+ {
+ "end_outermost_loop": 62,
+ "end_region_line": 62,
+ "line": "\n",
+ "lineno": 62,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 62,
+ "start_region_line": 62
+ },
+ {
+ "end_outermost_loop": 63,
+ "end_region_line": 63,
+ "line": "\n",
+ "lineno": 63,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 63,
+ "start_region_line": 63
+ },
+ {
+ "end_outermost_loop": 79,
+ "end_region_line": 79,
+ "line": "def get_stretch_directory(sub_directory=''):\n",
+ "lineno": 64,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 64,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 65,
+ "end_region_line": 79,
+ "line": " \"\"\"Returns path to stretch_user dir if HELLO_FLEET_PATH env var exists\n",
+ "lineno": 65,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 65,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 66,
+ "end_region_line": 79,
+ "line": "\n",
+ "lineno": 66,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 66,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 67,
+ "end_region_line": 79,
+ "line": " Parameters\n",
+ "lineno": 67,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 67,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 68,
+ "end_region_line": 79,
+ "line": " ----------\n",
+ "lineno": 68,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 68,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 69,
+ "end_region_line": 79,
+ "line": " sub_directory : str\n",
+ "lineno": 69,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 69,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 70,
+ "end_region_line": 79,
+ "line": " valid sub_directory within stretch_user/\n",
+ "lineno": 70,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 70,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 71,
+ "end_region_line": 79,
+ "line": "\n",
+ "lineno": 71,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 71,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 72,
+ "end_region_line": 79,
+ "line": " Returns\n",
+ "lineno": 72,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 72,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 73,
+ "end_region_line": 79,
+ "line": " -------\n",
+ "lineno": 73,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 73,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 74,
+ "end_region_line": 79,
+ "line": " str\n",
+ "lineno": 74,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 74,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 75,
+ "end_region_line": 79,
+ "line": " dirpath to stretch_user/ or dir within it if stretch_user/ exists, else /tmp\n",
+ "lineno": 75,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 75,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 76,
+ "end_region_line": 79,
+ "line": " \"\"\"\n",
+ "lineno": 76,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 76,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 77,
+ "end_region_line": 79,
+ "line": " base_path = os.environ.get('HELLO_FLEET_PATH', None)\n",
+ "lineno": 77,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 77,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 78,
+ "end_region_line": 79,
+ "line": " full_path = base_path + '/' + sub_directory if base_path is not None else '/tmp/'\n",
+ "lineno": 78,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 78,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 79,
+ "end_region_line": 79,
+ "line": " return full_path\n",
+ "lineno": 79,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 79,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 80,
+ "end_region_line": 80,
+ "line": "\n",
+ "lineno": 80,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 80,
+ "start_region_line": 80
+ },
+ {
+ "end_outermost_loop": 104,
+ "end_region_line": 104,
+ "line": "def read_fleet_yaml(f,fleet_dir=None):\n",
+ "lineno": 81,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 81,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 82,
+ "end_region_line": 104,
+ "line": " \"\"\"Reads yaml by filename from fleet directory\n",
+ "lineno": 82,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 82,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 83,
+ "end_region_line": 104,
+ "line": "\n",
+ "lineno": 83,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 83,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 84,
+ "end_region_line": 104,
+ "line": " Parameters\n",
+ "lineno": 84,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 84,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 85,
+ "end_region_line": 104,
+ "line": " ----------\n",
+ "lineno": 85,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 85,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 86,
+ "end_region_line": 104,
+ "line": " f : str\n",
+ "lineno": 86,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 86,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 87,
+ "end_region_line": 104,
+ "line": " filename of the yaml\n",
+ "lineno": 87,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 87,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 88,
+ "end_region_line": 104,
+ "line": "\n",
+ "lineno": 88,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 88,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 89,
+ "end_region_line": 104,
+ "line": " Returns\n",
+ "lineno": 89,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 89,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 90,
+ "end_region_line": 104,
+ "line": " -------\n",
+ "lineno": 90,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 90,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 91,
+ "end_region_line": 104,
+ "line": " dict\n",
+ "lineno": 91,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 91,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 92,
+ "end_region_line": 104,
+ "line": " yaml as dictionary if valid file, else empty dict\n",
+ "lineno": 92,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 92,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 93,
+ "end_region_line": 104,
+ "line": " \"\"\"\n",
+ "lineno": 93,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 93,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 94,
+ "end_region_line": 104,
+ "line": " try:\n",
+ "lineno": 94,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 94,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 99,
+ "end_region_line": 104,
+ "line": " if fleet_dir is None:\n",
+ "lineno": 95,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 95,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 96,
+ "end_region_line": 104,
+ "line": " fleet_dir=get_fleet_directory()\n",
+ "lineno": 96,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 96,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 99,
+ "end_region_line": 104,
+ "line": " else:\n",
+ "lineno": 97,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 95,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 99,
+ "end_region_line": 104,
+ "line": " if fleet_dir[-1] != '/':\n",
+ "lineno": 98,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 98,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 99,
+ "end_region_line": 104,
+ "line": " fleet_dir = fleet_dir + '/'\n",
+ "lineno": 99,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 99,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 102,
+ "end_region_line": 104,
+ "line": " with open(fleet_dir+f, 'r') as s:\n",
+ "lineno": 100,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 100,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 101,
+ "end_region_line": 104,
+ "line": " p = yaml.load(s,Loader=yaml.FullLoader)\n",
+ "lineno": 101,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 101,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 102,
+ "end_region_line": 104,
+ "line": " return {} if p is None else p\n",
+ "lineno": 102,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 102,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 103,
+ "end_region_line": 104,
+ "line": " except IOError:\n",
+ "lineno": 103,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 103,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 104,
+ "end_region_line": 104,
+ "line": " return {}\n",
+ "lineno": 104,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 104,
+ "start_region_line": 81
+ },
+ {
+ "end_outermost_loop": 105,
+ "end_region_line": 105,
+ "line": "\n",
+ "lineno": 105,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 105,
+ "start_region_line": 105
+ },
+ {
+ "end_outermost_loop": 114,
+ "end_region_line": 114,
+ "line": "def write_fleet_yaml(fn,rp,fleet_dir=None,header=None):\n",
+ "lineno": 106,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 106,
+ "start_region_line": 106
+ },
+ {
+ "end_outermost_loop": 108,
+ "end_region_line": 114,
+ "line": " if fleet_dir is None:\n",
+ "lineno": 107,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 107,
+ "start_region_line": 106
+ },
+ {
+ "end_outermost_loop": 108,
+ "end_region_line": 114,
+ "line": " fleet_dir = get_fleet_directory()\n",
+ "lineno": 108,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 108,
+ "start_region_line": 106
+ },
+ {
+ "end_outermost_loop": 110,
+ "end_region_line": 114,
+ "line": " if fleet_dir[-1]!='/':\n",
+ "lineno": 109,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 109,
+ "start_region_line": 106
+ },
+ {
+ "end_outermost_loop": 110,
+ "end_region_line": 114,
+ "line": " fleet_dir+='/'\n",
+ "lineno": 110,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 110,
+ "start_region_line": 106
+ },
+ {
+ "end_outermost_loop": 114,
+ "end_region_line": 114,
+ "line": " with open(fleet_dir+fn, 'w') as yaml_file:\n",
+ "lineno": 111,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 111,
+ "start_region_line": 106
+ },
+ {
+ "end_outermost_loop": 113,
+ "end_region_line": 114,
+ "line": " if header is not None:\n",
+ "lineno": 112,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 112,
+ "start_region_line": 106
+ },
+ {
+ "end_outermost_loop": 113,
+ "end_region_line": 114,
+ "line": " yaml_file.write(header)\n",
+ "lineno": 113,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 113,
+ "start_region_line": 106
+ },
+ {
+ "end_outermost_loop": 114,
+ "end_region_line": 114,
+ "line": " yaml.dump(rp, yaml_file, default_flow_style=False)\n",
+ "lineno": 114,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 114,
+ "start_region_line": 106
+ },
+ {
+ "end_outermost_loop": 115,
+ "end_region_line": 115,
+ "line": "\n",
+ "lineno": 115,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 115,
+ "start_region_line": 115
+ },
+ {
+ "end_outermost_loop": 116,
+ "end_region_line": 116,
+ "line": "\n",
+ "lineno": 116,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 116,
+ "start_region_line": 116
+ },
+ {
+ "end_outermost_loop": 148,
+ "end_region_line": 148,
+ "line": "def overwrite_dict(overwritee_dict, overwriter_dict):\n",
+ "lineno": 117,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 118,
+ "end_region_line": 148,
+ "line": " \"\"\"Merge two dictionaries while overwriting common keys and\n",
+ "lineno": 118,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 118,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 119,
+ "end_region_line": 148,
+ "line": " report errors when values of the same key differ in Python\n",
+ "lineno": 119,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 119,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 120,
+ "end_region_line": 148,
+ "line": " type. The result gets stored in `overwritee_dict`.\n",
+ "lineno": 120,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 120,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 121,
+ "end_region_line": 148,
+ "line": "\n",
+ "lineno": 121,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 121,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 122,
+ "end_region_line": 148,
+ "line": " Parameters\n",
+ "lineno": 122,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 122,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 123,
+ "end_region_line": 148,
+ "line": " ----------\n",
+ "lineno": 123,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 123,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 124,
+ "end_region_line": 148,
+ "line": " overwritee_dict : dict\n",
+ "lineno": 124,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 124,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 125,
+ "end_region_line": 148,
+ "line": " The dictionary which will be overwritten. Use this as the merged result.\n",
+ "lineno": 125,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 125,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 126,
+ "end_region_line": 148,
+ "line": " overwriter_dict : dict\n",
+ "lineno": 126,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 126,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 127,
+ "end_region_line": 148,
+ "line": " The dictionary which will overwrite.\n",
+ "lineno": 127,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 127,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 128,
+ "end_region_line": 148,
+ "line": "\n",
+ "lineno": 128,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 128,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 129,
+ "end_region_line": 148,
+ "line": " Returns\n",
+ "lineno": 129,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 129,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 130,
+ "end_region_line": 148,
+ "line": " -------\n",
+ "lineno": 130,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 130,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 131,
+ "end_region_line": 148,
+ "line": " bool\n",
+ "lineno": 131,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 131,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 132,
+ "end_region_line": 148,
+ "line": " True if no mismatches were found during the overwrite, False otherwise.\n",
+ "lineno": 132,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 132,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 133,
+ "end_region_line": 148,
+ "line": " \"\"\"\n",
+ "lineno": 133,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 133,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 148,
+ "line": " no_mismatches = True\n",
+ "lineno": 134,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 134,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 147,
+ "end_region_line": 147,
+ "line": " for k in overwriter_dict.keys():\n",
+ "lineno": 135,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 135,
+ "start_region_line": 135
+ },
+ {
+ "end_outermost_loop": 147,
+ "end_region_line": 147,
+ "line": " if k in overwritee_dict:\n",
+ "lineno": 136,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 135,
+ "start_region_line": 135
+ },
+ {
+ "end_outermost_loop": 147,
+ "end_region_line": 147,
+ "line": " if (isinstance(overwritee_dict[k], dict) and isinstance(overwriter_dict[k], dict)):\n",
+ "lineno": 137,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 135,
+ "start_region_line": 135
+ },
+ {
+ "end_outermost_loop": 147,
+ "end_region_line": 147,
+ "line": " sub_no_mismatches = overwrite_dict(overwritee_dict[k], overwriter_dict[k])\n",
+ "lineno": 138,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 135,
+ "start_region_line": 135
+ },
+ {
+ "end_outermost_loop": 147,
+ "end_region_line": 147,
+ "line": " no_mismatches = no_mismatches and sub_no_mismatches\n",
+ "lineno": 139,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 135,
+ "start_region_line": 135
+ },
+ {
+ "end_outermost_loop": 147,
+ "end_region_line": 147,
+ "line": " else:\n",
+ "lineno": 140,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 135,
+ "start_region_line": 135
+ },
+ {
+ "end_outermost_loop": 147,
+ "end_region_line": 147,
+ "line": " if (type(overwritee_dict[k]) == type(overwriter_dict[k])) or (isinstance(overwritee_dict[k], numbers.Real) and isinstance(overwriter_dict[k], numbers.Real)):\n",
+ "lineno": 141,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 135,
+ "start_region_line": 135
+ },
+ {
+ "end_outermost_loop": 147,
+ "end_region_line": 147,
+ "line": " overwritee_dict[k] = overwriter_dict[k]\n",
+ "lineno": 142,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 135,
+ "start_region_line": 135
+ },
+ {
+ "end_outermost_loop": 147,
+ "end_region_line": 147,
+ "line": " else:\n",
+ "lineno": 143,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 135,
+ "start_region_line": 135
+ },
+ {
+ "end_outermost_loop": 147,
+ "end_region_line": 147,
+ "line": " no_mismatches = False\n",
+ "lineno": 144,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 135,
+ "start_region_line": 135
+ },
+ {
+ "end_outermost_loop": 147,
+ "end_region_line": 147,
+ "line": " print('stretch_body.hello_utils.overwrite_dict ERROR: Type mismatch for key={0}, between overwritee={1} and overwriter={2}'.format(k, overwritee_dict[k], overwriter_dict[k]), file=sys.stderr)\n",
+ "lineno": 145,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 135,
+ "start_region_line": 135
+ },
+ {
+ "end_outermost_loop": 147,
+ "end_region_line": 147,
+ "line": " else: #If key not present, add anyhow (useful for overlaying params)\n",
+ "lineno": 146,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 135,
+ "start_region_line": 135
+ },
+ {
+ "end_outermost_loop": 147,
+ "end_region_line": 147,
+ "line": " overwritee_dict[k] = overwriter_dict[k]\n",
+ "lineno": 147,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 135,
+ "start_region_line": 135
+ },
+ {
+ "end_outermost_loop": 148,
+ "end_region_line": 148,
+ "line": " return no_mismatches\n",
+ "lineno": 148,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 148,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 149,
+ "end_region_line": 149,
+ "line": "\n",
+ "lineno": 149,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 149,
+ "start_region_line": 149
+ },
+ {
+ "end_outermost_loop": 166,
+ "end_region_line": 166,
+ "line": "def pretty_print_dict(title, d):\n",
+ "lineno": 150,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 150,
+ "start_region_line": 150
+ },
+ {
+ "end_outermost_loop": 151,
+ "end_region_line": 166,
+ "line": " \"\"\"Print human readable representation of dictionary to terminal\n",
+ "lineno": 151,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 151,
+ "start_region_line": 150
+ },
+ {
+ "end_outermost_loop": 152,
+ "end_region_line": 166,
+ "line": "\n",
+ "lineno": 152,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 152,
+ "start_region_line": 150
+ },
+ {
+ "end_outermost_loop": 153,
+ "end_region_line": 166,
+ "line": " Parameters\n",
+ "lineno": 153,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 153,
+ "start_region_line": 150
+ },
+ {
+ "end_outermost_loop": 154,
+ "end_region_line": 166,
+ "line": " ----------\n",
+ "lineno": 154,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 154,
+ "start_region_line": 150
+ },
+ {
+ "end_outermost_loop": 155,
+ "end_region_line": 166,
+ "line": " title : str\n",
+ "lineno": 155,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 155,
+ "start_region_line": 150
+ },
+ {
+ "end_outermost_loop": 156,
+ "end_region_line": 166,
+ "line": " header title under which the dictionary is printed\n",
+ "lineno": 156,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 156,
+ "start_region_line": 150
+ },
+ {
+ "end_outermost_loop": 157,
+ "end_region_line": 166,
+ "line": " d : dict\n",
+ "lineno": 157,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 157,
+ "start_region_line": 150
+ },
+ {
+ "end_outermost_loop": 158,
+ "end_region_line": 166,
+ "line": " the dictionary to pretty print\n",
+ "lineno": 158,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 158,
+ "start_region_line": 150
+ },
+ {
+ "end_outermost_loop": 159,
+ "end_region_line": 166,
+ "line": " \"\"\"\n",
+ "lineno": 159,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 159,
+ "start_region_line": 150
+ },
+ {
+ "end_outermost_loop": 160,
+ "end_region_line": 166,
+ "line": " print('-------- {0} --------'.format(title))\n",
+ "lineno": 160,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 160,
+ "start_region_line": 150
+ },
+ {
+ "end_outermost_loop": 163,
+ "end_region_line": 163,
+ "line": " for k in d.keys():\n",
+ "lineno": 161,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 161,
+ "start_region_line": 161
+ },
+ {
+ "end_outermost_loop": 163,
+ "end_region_line": 163,
+ "line": " if type(d[k]) != dict:\n",
+ "lineno": 162,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 161,
+ "start_region_line": 161
+ },
+ {
+ "end_outermost_loop": 163,
+ "end_region_line": 163,
+ "line": " print(k, ' : ', d[k])\n",
+ "lineno": 163,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 161,
+ "start_region_line": 161
+ },
+ {
+ "end_outermost_loop": 166,
+ "end_region_line": 166,
+ "line": " for k in d.keys():\n",
+ "lineno": 164,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 164,
+ "start_region_line": 164
+ },
+ {
+ "end_outermost_loop": 166,
+ "end_region_line": 166,
+ "line": " if type(d[k]) == dict:\n",
+ "lineno": 165,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 164,
+ "start_region_line": 164
+ },
+ {
+ "end_outermost_loop": 166,
+ "end_region_line": 166,
+ "line": " pretty_print_dict(k, d[k])\n",
+ "lineno": 166,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 164,
+ "start_region_line": 164
+ },
+ {
+ "end_outermost_loop": 167,
+ "end_region_line": 167,
+ "line": "\n",
+ "lineno": 167,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 167,
+ "start_region_line": 167
+ },
+ {
+ "end_outermost_loop": 168,
+ "end_region_line": 168,
+ "line": "\n",
+ "lineno": 168,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 168,
+ "start_region_line": 168
+ },
+ {
+ "end_outermost_loop": 169,
+ "end_region_line": 169,
+ "line": "\n",
+ "lineno": 169,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 169,
+ "start_region_line": 169
+ },
+ {
+ "end_outermost_loop": 283,
+ "end_region_line": 283,
+ "line": "class LoopStats():\n",
+ "lineno": 170,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 170,
+ "start_region_line": 170
+ },
+ {
+ "end_outermost_loop": 171,
+ "end_region_line": 283,
+ "line": " \"\"\"Track timing statistics for control loops\n",
+ "lineno": 171,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 171,
+ "start_region_line": 170
+ },
+ {
+ "end_outermost_loop": 172,
+ "end_region_line": 283,
+ "line": " \"\"\"\n",
+ "lineno": 172,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 172,
+ "start_region_line": 170
+ },
+ {
+ "end_outermost_loop": 173,
+ "end_region_line": 283,
+ "line": "\n",
+ "lineno": 173,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 173,
+ "start_region_line": 170
+ },
+ {
+ "end_outermost_loop": 195,
+ "end_region_line": 195,
+ "line": " def __init__(self, loop_name, target_loop_rate):\n",
+ "lineno": 174,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 174,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 175,
+ "end_region_line": 195,
+ "line": " self.loop_name = loop_name\n",
+ "lineno": 175,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 175,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 176,
+ "end_region_line": 195,
+ "line": " self.target_loop_rate = target_loop_rate\n",
+ "lineno": 176,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 176,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 177,
+ "end_region_line": 195,
+ "line": " self.ts_loop_start = None\n",
+ "lineno": 177,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 177,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 178,
+ "end_region_line": 195,
+ "line": " self.ts_loop_end = None\n",
+ "lineno": 178,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 178,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 179,
+ "end_region_line": 195,
+ "line": " self.last_ts_loop_start = None\n",
+ "lineno": 179,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 179,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 180,
+ "end_region_line": 195,
+ "line": " self.status = {'execution_time_s': 0,\n",
+ "lineno": 180,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 180,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 181,
+ "end_region_line": 195,
+ "line": " 'curr_rate_hz': 0,\n",
+ "lineno": 181,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 181,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 182,
+ "end_region_line": 195,
+ "line": " 'avg_rate_hz': 0,\n",
+ "lineno": 182,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 182,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 183,
+ "end_region_line": 195,
+ "line": " 'supportable_rate_hz': 0,\n",
+ "lineno": 183,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 183,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 184,
+ "end_region_line": 195,
+ "line": " 'min_rate_hz': float('inf'),\n",
+ "lineno": 184,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 184,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 185,
+ "end_region_line": 195,
+ "line": " 'max_rate_hz': 0,\n",
+ "lineno": 185,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 185,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 186,
+ "end_region_line": 195,
+ "line": " 'std_rate_hz': 0,\n",
+ "lineno": 186,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 186,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 187,
+ "end_region_line": 195,
+ "line": " 'missed_loops': 0,\n",
+ "lineno": 187,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 187,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 188,
+ "end_region_line": 195,
+ "line": " 'num_loops': 0}\n",
+ "lineno": 188,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 188,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 189,
+ "end_region_line": 195,
+ "line": " self.logger = logging.getLogger(self.loop_name)\n",
+ "lineno": 189,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 189,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 190,
+ "end_region_line": 195,
+ "line": " self.curr_rate_history = []\n",
+ "lineno": 190,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 190,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 191,
+ "end_region_line": 195,
+ "line": " self.supportable_rate_history = []\n",
+ "lineno": 191,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 191,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 192,
+ "end_region_line": 195,
+ "line": " self.n_history = 100\n",
+ "lineno": 192,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 192,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 193,
+ "end_region_line": 195,
+ "line": " self.debug_freq = 50\n",
+ "lineno": 193,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 193,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 194,
+ "end_region_line": 195,
+ "line": " self.sleep_time_s = 0.0\n",
+ "lineno": 194,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 194,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 195,
+ "end_region_line": 195,
+ "line": " self.ts_0=time.time()\n",
+ "lineno": 195,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 195,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 196,
+ "end_region_line": 283,
+ "line": "\n",
+ "lineno": 196,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 196,
+ "start_region_line": 170
+ },
+ {
+ "end_outermost_loop": 206,
+ "end_region_line": 206,
+ "line": " def pretty_print(self):\n",
+ "lineno": 197,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 197,
+ "start_region_line": 197
+ },
+ {
+ "end_outermost_loop": 198,
+ "end_region_line": 206,
+ "line": " print('--------- TimingStats %s -----------' % self.loop_name)\n",
+ "lineno": 198,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 198,
+ "start_region_line": 197
+ },
+ {
+ "end_outermost_loop": 199,
+ "end_region_line": 206,
+ "line": " print('Target rate (Hz): %.2f' % self.target_loop_rate)\n",
+ "lineno": 199,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 199,
+ "start_region_line": 197
+ },
+ {
+ "end_outermost_loop": 200,
+ "end_region_line": 206,
+ "line": " print('Current rate (Hz): %.2f' % self.status['curr_rate_hz'])\n",
+ "lineno": 200,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 200,
+ "start_region_line": 197
+ },
+ {
+ "end_outermost_loop": 201,
+ "end_region_line": 206,
+ "line": " print('Average rate (Hz): %.2f' % self.status['avg_rate_hz'])\n",
+ "lineno": 201,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 201,
+ "start_region_line": 197
+ },
+ {
+ "end_outermost_loop": 202,
+ "end_region_line": 206,
+ "line": " print('Standard deviation of rate history (Hz): %.2f' % self.status['std_rate_hz'])\n",
+ "lineno": 202,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 202,
+ "start_region_line": 197
+ },
+ {
+ "end_outermost_loop": 203,
+ "end_region_line": 206,
+ "line": " print('Min rate (Hz): %.2f' % self.status['min_rate_hz'])\n",
+ "lineno": 203,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 203,
+ "start_region_line": 197
+ },
+ {
+ "end_outermost_loop": 204,
+ "end_region_line": 206,
+ "line": " print('Max rate (Hz): %.2f' % self.status['max_rate_hz'])\n",
+ "lineno": 204,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 204,
+ "start_region_line": 197
+ },
+ {
+ "end_outermost_loop": 205,
+ "end_region_line": 206,
+ "line": " print('Supportable rate (Hz): %.2f' % self.status['supportable_rate_hz'])\n",
+ "lineno": 205,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 205,
+ "start_region_line": 197
+ },
+ {
+ "end_outermost_loop": 206,
+ "end_region_line": 206,
+ "line": " print('Warnings: %d out of %d' % (self.status['missed_loops'], self.status['num_loops']))\n",
+ "lineno": 206,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 206,
+ "start_region_line": 197
+ },
+ {
+ "end_outermost_loop": 207,
+ "end_region_line": 283,
+ "line": "\n",
+ "lineno": 207,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 207,
+ "start_region_line": 170
+ },
+ {
+ "end_outermost_loop": 253,
+ "end_region_line": 253,
+ "line": " def mark_loop_start(self):\n",
+ "lineno": 208,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 208,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 209,
+ "end_region_line": 253,
+ "line": " self.status['num_loops'] += 1\n",
+ "lineno": 209,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 209,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 210,
+ "end_region_line": 253,
+ "line": " self.ts_loop_start=time.time()\n",
+ "lineno": 210,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 210,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 211,
+ "end_region_line": 253,
+ "line": "\n",
+ "lineno": 211,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 211,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 214,
+ "end_region_line": 253,
+ "line": " if self.last_ts_loop_start is None: #Wait until have sufficient data\n",
+ "lineno": 212,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 212,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 213,
+ "end_region_line": 253,
+ "line": " self.last_ts_loop_start=self.ts_loop_start\n",
+ "lineno": 213,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 213,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 214,
+ "end_region_line": 253,
+ "line": " return\n",
+ "lineno": 214,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 214,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 215,
+ "end_region_line": 253,
+ "line": "\n",
+ "lineno": 215,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 215,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 216,
+ "end_region_line": 253,
+ "line": " self.status['curr_rate_hz'] = 1.0 / (self.ts_loop_start - self.last_ts_loop_start)\n",
+ "lineno": 216,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 216,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 217,
+ "end_region_line": 253,
+ "line": " self.status['min_rate_hz'] = min(self.status['curr_rate_hz'], self.status['min_rate_hz'])\n",
+ "lineno": 217,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 217,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 218,
+ "end_region_line": 253,
+ "line": " self.status['max_rate_hz'] = max(self.status['curr_rate_hz'], self.status['max_rate_hz'])\n",
+ "lineno": 218,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 218,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 219,
+ "end_region_line": 253,
+ "line": "\n",
+ "lineno": 219,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 219,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 220,
+ "end_region_line": 253,
+ "line": "\n",
+ "lineno": 220,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 220,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 253,
+ "end_region_line": 253,
+ "line": " # Calculate average and supportable loop rate **must be done before marking loop end**\n",
+ "lineno": 221,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 208,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 223,
+ "end_region_line": 253,
+ "line": " if len(self.curr_rate_history) \\u003e= self.n_history:\n",
+ "lineno": 222,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 222,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 223,
+ "end_region_line": 253,
+ "line": " self.curr_rate_history.pop(0)\n",
+ "lineno": 223,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 223,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 224,
+ "end_region_line": 253,
+ "line": " self.curr_rate_history.append(self.status['curr_rate_hz'])\n",
+ "lineno": 224,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 224,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 225,
+ "end_region_line": 253,
+ "line": " self.status['avg_rate_hz'] = np.mean(self.curr_rate_history)\n",
+ "lineno": 225,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 225,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 226,
+ "end_region_line": 253,
+ "line": " self.status['std_rate_hz'] = np.std(self.curr_rate_history)\n",
+ "lineno": 226,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 226,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 228,
+ "end_region_line": 253,
+ "line": " if len(self.supportable_rate_history) \\u003e= self.n_history:\n",
+ "lineno": 227,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 227,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 228,
+ "end_region_line": 253,
+ "line": " self.supportable_rate_history.pop(0)\n",
+ "lineno": 228,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 228,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 229,
+ "end_region_line": 253,
+ "line": " self.supportable_rate_history.append(1.0 / self.status['execution_time_s'])\n",
+ "lineno": 229,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 229,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 230,
+ "end_region_line": 253,
+ "line": " self.status['supportable_rate_hz'] = np.mean(self.supportable_rate_history)\n",
+ "lineno": 230,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 230,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 231,
+ "end_region_line": 253,
+ "line": "\n",
+ "lineno": 231,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 231,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 253,
+ "end_region_line": 253,
+ "line": " # Log timing stats **must be done before marking loop end**\n",
+ "lineno": 232,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 208,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 244,
+ "end_region_line": 253,
+ "line": " if self.status['num_loops'] % self.debug_freq == 0:\n",
+ "lineno": 233,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 233,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 234,
+ "end_region_line": 253,
+ "line": " self.logger.debug('--------- TimingStats %s %d -----------' % (self.loop_name, self.status['num_loops']))\n",
+ "lineno": 234,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 234,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 235,
+ "end_region_line": 253,
+ "line": " self.logger.debug('Target rate: %f' % self.target_loop_rate)\n",
+ "lineno": 235,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 235,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 236,
+ "end_region_line": 253,
+ "line": " self.logger.debug('Current rate (Hz): %f' % self.status['curr_rate_hz'])\n",
+ "lineno": 236,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 236,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 237,
+ "end_region_line": 253,
+ "line": " self.logger.debug('Average rate (Hz): %f' % self.status['avg_rate_hz'])\n",
+ "lineno": 237,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 237,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 238,
+ "end_region_line": 253,
+ "line": " self.logger.debug('Standard deviation of rate history (Hz): %f' % self.status['std_rate_hz'])\n",
+ "lineno": 238,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 238,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 239,
+ "end_region_line": 253,
+ "line": " self.logger.debug('Min rate (Hz): %f' % self.status['min_rate_hz'])\n",
+ "lineno": 239,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 239,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 240,
+ "end_region_line": 253,
+ "line": " self.logger.debug('Max rate (Hz): %f' % self.status['max_rate_hz'])\n",
+ "lineno": 240,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 240,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 241,
+ "end_region_line": 253,
+ "line": " self.logger.debug('Supportable rate (Hz): %f' % self.status['supportable_rate_hz'])\n",
+ "lineno": 241,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 241,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 242,
+ "end_region_line": 253,
+ "line": " self.logger.debug('Standard deviation of supportable rate history (Hz): %f' % np.std(self.supportable_rate_history))\n",
+ "lineno": 242,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 242,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 243,
+ "end_region_line": 253,
+ "line": " self.logger.debug('Warnings: %d out of %d' % (self.status['missed_loops'], self.status['num_loops']))\n",
+ "lineno": 243,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 243,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 244,
+ "end_region_line": 253,
+ "line": " self.logger.debug('Sleep time (s): %f' % self.sleep_time_s)\n",
+ "lineno": 244,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 244,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 245,
+ "end_region_line": 253,
+ "line": "\n",
+ "lineno": 245,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 245,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 246,
+ "end_region_line": 253,
+ "line": " self.last_ts_loop_start = self.ts_loop_start\n",
+ "lineno": 246,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 246,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 247,
+ "end_region_line": 253,
+ "line": "\n",
+ "lineno": 247,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 247,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 253,
+ "end_region_line": 253,
+ "line": " # Calculate sleep time to achieve desired loop rate\n",
+ "lineno": 248,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 208,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 249,
+ "end_region_line": 253,
+ "line": " self.sleep_time_s = (1 / self.target_loop_rate) - self.status['execution_time_s']\n",
+ "lineno": 249,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 249,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 253,
+ "end_region_line": 253,
+ "line": " if self.sleep_time_s \\u003c 0.0 and time.time()-self.ts_0\\u003e5.0: #Allow 5s for timing to stabilize on startup\n",
+ "lineno": 250,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 250,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 251,
+ "end_region_line": 253,
+ "line": " self.status['missed_loops'] += 1\n",
+ "lineno": 251,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 251,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 253,
+ "end_region_line": 253,
+ "line": " if self.status['missed_loops'] == 1:\n",
+ "lineno": 252,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 252,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 253,
+ "end_region_line": 253,
+ "line": " self.logger.debug('Missed target loop rate of %.2f Hz for %s. Currently %.2f Hz' % (self.target_loop_rate, self.loop_name, self.status['curr_rate_hz']))\n",
+ "lineno": 253,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 253,
+ "start_region_line": 208
+ },
+ {
+ "end_outermost_loop": 254,
+ "end_region_line": 283,
+ "line": "\n",
+ "lineno": 254,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 254,
+ "start_region_line": 170
+ },
+ {
+ "end_outermost_loop": 260,
+ "end_region_line": 260,
+ "line": " def mark_loop_end(self):\n",
+ "lineno": 255,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 255,
+ "start_region_line": 255
+ },
+ {
+ "end_outermost_loop": 260,
+ "end_region_line": 260,
+ "line": " # First two cycles initialize vars / log\n",
+ "lineno": 256,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 255,
+ "start_region_line": 255
+ },
+ {
+ "end_outermost_loop": 258,
+ "end_region_line": 260,
+ "line": " if self.ts_loop_start is None:\n",
+ "lineno": 257,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 257,
+ "start_region_line": 255
+ },
+ {
+ "end_outermost_loop": 258,
+ "end_region_line": 260,
+ "line": " return\n",
+ "lineno": 258,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 258,
+ "start_region_line": 255
+ },
+ {
+ "end_outermost_loop": 259,
+ "end_region_line": 260,
+ "line": " self.ts_loop_end = time.time()\n",
+ "lineno": 259,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 259,
+ "start_region_line": 255
+ },
+ {
+ "end_outermost_loop": 260,
+ "end_region_line": 260,
+ "line": " self.status['execution_time_s'] = self.ts_loop_end - self.ts_loop_start\n",
+ "lineno": 260,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 260,
+ "start_region_line": 255
+ },
+ {
+ "end_outermost_loop": 261,
+ "end_region_line": 283,
+ "line": "\n",
+ "lineno": 261,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 261,
+ "start_region_line": 170
+ },
+ {
+ "end_outermost_loop": 262,
+ "end_region_line": 283,
+ "line": "\n",
+ "lineno": 262,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 262,
+ "start_region_line": 170
+ },
+ {
+ "end_outermost_loop": 268,
+ "end_region_line": 268,
+ "line": " def generate_rate_histogram(self, save=None):\n",
+ "lineno": 263,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 263,
+ "start_region_line": 263
+ },
+ {
+ "end_outermost_loop": 264,
+ "end_region_line": 268,
+ "line": " import matplotlib.pyplot as plt\n",
+ "lineno": 264,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 264,
+ "start_region_line": 263
+ },
+ {
+ "end_outermost_loop": 265,
+ "end_region_line": 268,
+ "line": " fig, axs = plt.subplots(1, 1, sharey=True, tight_layout=True)\n",
+ "lineno": 265,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 265,
+ "start_region_line": 263
+ },
+ {
+ "end_outermost_loop": 266,
+ "end_region_line": 268,
+ "line": " fig.suptitle('Distribution of loop rate (Hz). Target of %.2f ' % self.target_loop_rate)\n",
+ "lineno": 266,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 266,
+ "start_region_line": 263
+ },
+ {
+ "end_outermost_loop": 267,
+ "end_region_line": 268,
+ "line": " axs.hist(x=self.curr_rate_history, bins='auto', color='#0504aa', alpha=0.7, rwidth=0.85)\n",
+ "lineno": 267,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 267,
+ "start_region_line": 263
+ },
+ {
+ "end_outermost_loop": 268,
+ "end_region_line": 268,
+ "line": " plt.show() if save is None else plt.savefig(save)\n",
+ "lineno": 268,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 268,
+ "start_region_line": 263
+ },
+ {
+ "end_outermost_loop": 269,
+ "end_region_line": 283,
+ "line": "\n",
+ "lineno": 269,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 269,
+ "start_region_line": 170
+ },
+ {
+ "end_outermost_loop": 276,
+ "end_region_line": 276,
+ "line": " def get_loop_sleep_time(self):\n",
+ "lineno": 270,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 270,
+ "start_region_line": 270
+ },
+ {
+ "end_outermost_loop": 271,
+ "end_region_line": 276,
+ "line": " \"\"\"\n",
+ "lineno": 271,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 271,
+ "start_region_line": 270
+ },
+ {
+ "end_outermost_loop": 272,
+ "end_region_line": 276,
+ "line": " Returns\n",
+ "lineno": 272,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 272,
+ "start_region_line": 270
+ },
+ {
+ "end_outermost_loop": 273,
+ "end_region_line": 276,
+ "line": " -------\n",
+ "lineno": 273,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 273,
+ "start_region_line": 270
+ },
+ {
+ "end_outermost_loop": 274,
+ "end_region_line": 276,
+ "line": " float : Time to sleep for to hit target loop rate\n",
+ "lineno": 274,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 274,
+ "start_region_line": 270
+ },
+ {
+ "end_outermost_loop": 275,
+ "end_region_line": 276,
+ "line": " \"\"\"\n",
+ "lineno": 275,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 275,
+ "start_region_line": 270
+ },
+ {
+ "end_outermost_loop": 276,
+ "end_region_line": 276,
+ "line": " return max(0.0, self.sleep_time_s)\n",
+ "lineno": 276,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 276,
+ "start_region_line": 270
+ },
+ {
+ "end_outermost_loop": 277,
+ "end_region_line": 283,
+ "line": "\n",
+ "lineno": 277,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 277,
+ "start_region_line": 170
+ },
+ {
+ "end_outermost_loop": 283,
+ "end_region_line": 283,
+ "line": " def wait_until_ready_to_run(self,sleep=.0005):\n",
+ "lineno": 278,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 278,
+ "start_region_line": 278
+ },
+ {
+ "end_outermost_loop": 281,
+ "end_region_line": 283,
+ "line": " if self.ts_loop_start is None:\n",
+ "lineno": 279,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 279,
+ "start_region_line": 278
+ },
+ {
+ "end_outermost_loop": 280,
+ "end_region_line": 283,
+ "line": " time.sleep(.01)\n",
+ "lineno": 280,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 280,
+ "start_region_line": 278
+ },
+ {
+ "end_outermost_loop": 281,
+ "end_region_line": 283,
+ "line": " return True\n",
+ "lineno": 281,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 281,
+ "start_region_line": 278
+ },
+ {
+ "end_outermost_loop": 283,
+ "end_region_line": 283,
+ "line": " while time.time()-self.ts_loop_start\\u003c(1/self.target_loop_rate):\n",
+ "lineno": 282,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 282,
+ "start_region_line": 282
+ },
+ {
+ "end_outermost_loop": 283,
+ "end_region_line": 283,
+ "line": " time.sleep(sleep)\n",
+ "lineno": 283,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 282,
+ "start_region_line": 282
+ },
+ {
+ "end_outermost_loop": 284,
+ "end_region_line": 284,
+ "line": "\n",
+ "lineno": 284,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 284,
+ "start_region_line": 284
+ },
+ {
+ "end_outermost_loop": 285,
+ "end_region_line": 285,
+ "line": "\n",
+ "lineno": 285,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 285,
+ "start_region_line": 285
+ },
+ {
+ "end_outermost_loop": 291,
+ "end_region_line": 291,
+ "line": "class ThreadServiceExit(Exception):\n",
+ "lineno": 286,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 286,
+ "start_region_line": 286
+ },
+ {
+ "end_outermost_loop": 287,
+ "end_region_line": 291,
+ "line": " \"\"\"\n",
+ "lineno": 287,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 287,
+ "start_region_line": 286
+ },
+ {
+ "end_outermost_loop": 288,
+ "end_region_line": 291,
+ "line": " Custom exception which is used to trigger the clean exit\n",
+ "lineno": 288,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 288,
+ "start_region_line": 286
+ },
+ {
+ "end_outermost_loop": 289,
+ "end_region_line": 291,
+ "line": " of all running threads and the main program.\n",
+ "lineno": 289,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 289,
+ "start_region_line": 286
+ },
+ {
+ "end_outermost_loop": 290,
+ "end_region_line": 291,
+ "line": " \"\"\"\n",
+ "lineno": 290,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 290,
+ "start_region_line": 286
+ },
+ {
+ "end_outermost_loop": 291,
+ "end_region_line": 291,
+ "line": " pass\n",
+ "lineno": 291,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 291,
+ "start_region_line": 286
+ },
+ {
+ "end_outermost_loop": 292,
+ "end_region_line": 292,
+ "line": "\n",
+ "lineno": 292,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 292,
+ "start_region_line": 292
+ },
+ {
+ "end_outermost_loop": 293,
+ "end_region_line": 293,
+ "line": "#Signal handler, must be set from main thread\n",
+ "lineno": 293,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 293,
+ "start_region_line": 293
+ },
+ {
+ "end_outermost_loop": 296,
+ "end_region_line": 296,
+ "line": "def thread_service_shutdown(signum, frame):\n",
+ "lineno": 294,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 294,
+ "start_region_line": 294
+ },
+ {
+ "end_outermost_loop": 295,
+ "end_region_line": 296,
+ "line": " print('Caught signal %d' % signum)\n",
+ "lineno": 295,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 295,
+ "start_region_line": 294
+ },
+ {
+ "end_outermost_loop": 296,
+ "end_region_line": 296,
+ "line": " raise ThreadServiceExit\n",
+ "lineno": 296,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 296,
+ "start_region_line": 294
+ },
+ {
+ "end_outermost_loop": 297,
+ "end_region_line": 297,
+ "line": "\n",
+ "lineno": 297,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 297,
+ "start_region_line": 297
+ },
+ {
+ "end_outermost_loop": 319,
+ "end_region_line": 319,
+ "line": "def evaluate_polynomial_at(poly, t):\n",
+ "lineno": 298,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 298,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 299,
+ "end_region_line": 319,
+ "line": " \"\"\"Evaluate a quintic polynomial at a given time.\n",
+ "lineno": 299,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 299,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 300,
+ "end_region_line": 319,
+ "line": "\n",
+ "lineno": 300,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 300,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 301,
+ "end_region_line": 319,
+ "line": " Parameters\n",
+ "lineno": 301,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 301,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 302,
+ "end_region_line": 319,
+ "line": " ----------\n",
+ "lineno": 302,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 302,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 303,
+ "end_region_line": 319,
+ "line": " poly : List(float)\n",
+ "lineno": 303,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 303,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 304,
+ "end_region_line": 319,
+ "line": " Represents a quintic polynomial as a coefficients array [a0, a1, a2, a3, a4, a5].\n",
+ "lineno": 304,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 304,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 305,
+ "end_region_line": 319,
+ "line": " The polynomial is f(t) = a0 + a1*t + a2*t^2 + a3*t^3 + a4*t^4 + a5*t^5\n",
+ "lineno": 305,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 305,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 306,
+ "end_region_line": 319,
+ "line": " t : float\n",
+ "lineno": 306,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 306,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 307,
+ "end_region_line": 319,
+ "line": " the time in seconds at which to evaluate the polynomial\n",
+ "lineno": 307,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 307,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 308,
+ "end_region_line": 319,
+ "line": "\n",
+ "lineno": 308,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 308,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 309,
+ "end_region_line": 319,
+ "line": " Returns\n",
+ "lineno": 309,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 309,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 310,
+ "end_region_line": 319,
+ "line": " -------\n",
+ "lineno": 310,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 310,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 311,
+ "end_region_line": 319,
+ "line": " Tuple(float)\n",
+ "lineno": 311,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 311,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 312,
+ "end_region_line": 319,
+ "line": " array with three elements: evaluated position, velocity, and acceleration.\n",
+ "lineno": 312,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 312,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 313,
+ "end_region_line": 319,
+ "line": " \"\"\"\n",
+ "lineno": 313,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 313,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 314,
+ "end_region_line": 319,
+ "line": " a = [float(elem) for elem in poly]\n",
+ "lineno": 314,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 314,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 315,
+ "end_region_line": 319,
+ "line": " t = float(t)\n",
+ "lineno": 315,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 315,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 316,
+ "end_region_line": 319,
+ "line": " pos = a[0] + (a[1]*t) + (a[2]*t**2) + (a[3]*t**3) + (a[4]*t**4) + (a[5]*t**5)\n",
+ "lineno": 316,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 316,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 317,
+ "end_region_line": 319,
+ "line": " vel = a[1] + (2*a[2]*t) + (3*a[3]*t**2) + (4*a[4]*t**3) + (5*a[5]*t**4)\n",
+ "lineno": 317,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 317,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 318,
+ "end_region_line": 319,
+ "line": " accel = (2*a[2]) + (6*a[3]*t) + (12*a[4]*t**2) + (20*a[5]*t**3)\n",
+ "lineno": 318,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 318,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 319,
+ "end_region_line": 319,
+ "line": " return (pos, vel, accel)\n",
+ "lineno": 319,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 319,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 320,
+ "end_region_line": 320,
+ "line": "\n",
+ "lineno": 320,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 320,
+ "start_region_line": 320
+ },
+ {
+ "end_outermost_loop": 359,
+ "end_region_line": 359,
+ "line": "def is_segment_feasible(segment, v_des, a_des, t=0.0, inc=0.1):\n",
+ "lineno": 321,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 321,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 322,
+ "end_region_line": 359,
+ "line": " \"\"\"Determine whether a segment adheres to dynamic limits.\n",
+ "lineno": 322,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 322,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 323,
+ "end_region_line": 359,
+ "line": "\n",
+ "lineno": 323,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 323,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 324,
+ "end_region_line": 359,
+ "line": " Parameters\n",
+ "lineno": 324,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 324,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 325,
+ "end_region_line": 359,
+ "line": " ----------\n",
+ "lineno": 325,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 325,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 326,
+ "end_region_line": 359,
+ "line": " segment : List\n",
+ "lineno": 326,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 326,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 327,
+ "end_region_line": 359,
+ "line": " Represents a segment of a waypoint trajectory as a list of length eight,\n",
+ "lineno": 327,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 327,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 328,
+ "end_region_line": 359,
+ "line": " structured like [duration_s, a0, a1, a2, a3, a4, a5, segment_id].\n",
+ "lineno": 328,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 328,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 329,
+ "end_region_line": 359,
+ "line": " v_des : float\n",
+ "lineno": 329,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 329,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 330,
+ "end_region_line": 359,
+ "line": " Velocity limit that the segment shouldn't exceed\n",
+ "lineno": 330,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 330,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 331,
+ "end_region_line": 359,
+ "line": " a_des : float\n",
+ "lineno": 331,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 331,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 332,
+ "end_region_line": 359,
+ "line": " Acceleration limit that the segment shouldn't exceed\n",
+ "lineno": 332,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 332,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 333,
+ "end_region_line": 359,
+ "line": " t : float\n",
+ "lineno": 333,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 333,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 334,
+ "end_region_line": 359,
+ "line": " optional, time in seconds at which to begin checking segment\n",
+ "lineno": 334,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 334,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 335,
+ "end_region_line": 359,
+ "line": " inc : float\n",
+ "lineno": 335,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 335,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 336,
+ "end_region_line": 359,
+ "line": " optional, increment in seconds at which the polynomial is evaluated along the segment\n",
+ "lineno": 336,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 336,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 337,
+ "end_region_line": 359,
+ "line": "\n",
+ "lineno": 337,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 337,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 338,
+ "end_region_line": 359,
+ "line": " Returns\n",
+ "lineno": 338,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 338,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 339,
+ "end_region_line": 359,
+ "line": " -------\n",
+ "lineno": 339,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 339,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 340,
+ "end_region_line": 359,
+ "line": " success: bool\n",
+ "lineno": 340,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 340,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 341,
+ "end_region_line": 359,
+ "line": " whether the segment is feasible\n",
+ "lineno": 341,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 341,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 342,
+ "end_region_line": 359,
+ "line": " max_v: float\n",
+ "lineno": 342,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 342,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 343,
+ "end_region_line": 359,
+ "line": " Maximum velocity of spline\n",
+ "lineno": 343,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 343,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 344,
+ "end_region_line": 359,
+ "line": " max_a: float\n",
+ "lineno": 344,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 344,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 345,
+ "end_region_line": 359,
+ "line": " Maximum acceleration of spline\n",
+ "lineno": 345,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 345,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 346,
+ "end_region_line": 359,
+ "line": " \"\"\"\n",
+ "lineno": 346,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 346,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 347,
+ "end_region_line": 359,
+ "line": " v_des = float(v_des)\n",
+ "lineno": 347,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 347,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 348,
+ "end_region_line": 359,
+ "line": " a_des = float(a_des)\n",
+ "lineno": 348,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 348,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 349,
+ "end_region_line": 359,
+ "line": " max_v = 0\n",
+ "lineno": 349,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 349,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 350,
+ "end_region_line": 359,
+ "line": " max_a =0\n",
+ "lineno": 350,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 350,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 351,
+ "end_region_line": 359,
+ "line": " success=True\n",
+ "lineno": 351,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 351,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 358,
+ "end_region_line": 358,
+ "line": " while t \\u003c segment[0]:\n",
+ "lineno": 352,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 352,
+ "start_region_line": 352
+ },
+ {
+ "end_outermost_loop": 358,
+ "end_region_line": 358,
+ "line": " x_t, vel_t, acc_t = evaluate_polynomial_at(segment[1:-1], t)\n",
+ "lineno": 353,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 352,
+ "start_region_line": 352
+ },
+ {
+ "end_outermost_loop": 358,
+ "end_region_line": 358,
+ "line": " max_v=max(max_v,abs(vel_t))\n",
+ "lineno": 354,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 352,
+ "start_region_line": 352
+ },
+ {
+ "end_outermost_loop": 358,
+ "end_region_line": 358,
+ "line": " max_a = max(max_a, abs(acc_t))\n",
+ "lineno": 355,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 352,
+ "start_region_line": 352
+ },
+ {
+ "end_outermost_loop": 358,
+ "end_region_line": 358,
+ "line": " if abs(vel_t) \\u003e v_des or abs(acc_t) \\u003e a_des:\n",
+ "lineno": 356,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 352,
+ "start_region_line": 352
+ },
+ {
+ "end_outermost_loop": 358,
+ "end_region_line": 358,
+ "line": " success=False\n",
+ "lineno": 357,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 352,
+ "start_region_line": 352
+ },
+ {
+ "end_outermost_loop": 358,
+ "end_region_line": 358,
+ "line": " t = min(segment[0], t + inc)\n",
+ "lineno": 358,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 352,
+ "start_region_line": 352
+ },
+ {
+ "end_outermost_loop": 359,
+ "end_region_line": 359,
+ "line": " return success, max_v, max_a\n",
+ "lineno": 359,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 359,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 360,
+ "end_region_line": 360,
+ "line": "\n",
+ "lineno": 360,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 360,
+ "start_region_line": 360
+ },
+ {
+ "end_outermost_loop": 386,
+ "end_region_line": 386,
+ "line": "def generate_quintic_polynomial(i, f):\n",
+ "lineno": 361,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 361,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 362,
+ "end_region_line": 386,
+ "line": " \"\"\"Generate quintic polynomial from two points\n",
+ "lineno": 362,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 362,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 363,
+ "end_region_line": 386,
+ "line": "\n",
+ "lineno": 363,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 363,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 364,
+ "end_region_line": 386,
+ "line": " Parameters\n",
+ "lineno": 364,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 364,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 365,
+ "end_region_line": 386,
+ "line": " ----------\n",
+ "lineno": 365,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 365,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 366,
+ "end_region_line": 386,
+ "line": " i : List(float)\n",
+ "lineno": 366,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 366,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 367,
+ "end_region_line": 386,
+ "line": " Represents the first waypoint as a list, [time, pos, vel, accel]\n",
+ "lineno": 367,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 367,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 368,
+ "end_region_line": 386,
+ "line": " f : List(float)\n",
+ "lineno": 368,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 368,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 369,
+ "end_region_line": 386,
+ "line": " Represents the second waypoint as a list, [time, pos, vel, accel]\n",
+ "lineno": 369,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 369,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 370,
+ "end_region_line": 386,
+ "line": "\n",
+ "lineno": 370,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 370,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 371,
+ "end_region_line": 386,
+ "line": " Returns\n",
+ "lineno": 371,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 371,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 372,
+ "end_region_line": 386,
+ "line": " -------\n",
+ "lineno": 372,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 372,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 373,
+ "end_region_line": 386,
+ "line": " List(float)\n",
+ "lineno": 373,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 373,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 374,
+ "end_region_line": 386,
+ "line": " Represents a quintic polynomial as a coefficients + duration array [duration, a0, a1, a2, a3, a4, a5].\n",
+ "lineno": 374,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 374,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 375,
+ "end_region_line": 386,
+ "line": " The polynomial is f(t) = a0 + a1*t + a2*t^2 + a3*t^3 + a4*t^4 + a5*t^5\n",
+ "lineno": 375,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 375,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 376,
+ "end_region_line": 386,
+ "line": " \"\"\"\n",
+ "lineno": 376,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 376,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 377,
+ "end_region_line": 386,
+ "line": " i = [float(elem) for elem in i]\n",
+ "lineno": 377,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 377,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 378,
+ "end_region_line": 386,
+ "line": " f = [float(elem) for elem in f]\n",
+ "lineno": 378,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 378,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 379,
+ "end_region_line": 386,
+ "line": " duration = f[0] - i[0]\n",
+ "lineno": 379,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 379,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 380,
+ "end_region_line": 386,
+ "line": " a0 = i[1]\n",
+ "lineno": 380,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 380,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 381,
+ "end_region_line": 386,
+ "line": " a1 = i[2]\n",
+ "lineno": 381,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 381,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 382,
+ "end_region_line": 386,
+ "line": " a2 = i[3] / 2\n",
+ "lineno": 382,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 382,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 383,
+ "end_region_line": 386,
+ "line": " a3 = (20 * f[1] - 20 * i[1] - (8 * f[2] + 12 * i[2]) * duration - (3 * i[3] - f[3]) * (duration ** 2)) / (2 * (duration ** 3))\n",
+ "lineno": 383,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 383,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 384,
+ "end_region_line": 386,
+ "line": " a4 = (30 * i[1] - 30 * f[1] + (14 * f[2] + 16 * i[2]) * duration + (3 * i[3] - 2 * f[3]) * (duration ** 2)) / (2 * (duration ** 4))\n",
+ "lineno": 384,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 384,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 385,
+ "end_region_line": 386,
+ "line": " a5 = (12 * f[1] - 12 * i[1] - (6 * f[2] + 6 * i[2]) * duration - (i[3] - f[3]) * (duration ** 2)) / (2 * (duration ** 5))\n",
+ "lineno": 385,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 385,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 386,
+ "end_region_line": 386,
+ "line": " return [duration, a0, a1, a2, a3, a4, a5]\n",
+ "lineno": 386,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 386,
+ "start_region_line": 361
+ },
+ {
+ "end_outermost_loop": 387,
+ "end_region_line": 387,
+ "line": "\n",
+ "lineno": 387,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 387,
+ "start_region_line": 387
+ },
+ {
+ "end_outermost_loop": 411,
+ "end_region_line": 411,
+ "line": "def generate_cubic_polynomial(i, f):\n",
+ "lineno": 388,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 388,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 389,
+ "end_region_line": 411,
+ "line": " \"\"\"Generate cubic polynomial from two points\n",
+ "lineno": 389,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 389,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 390,
+ "end_region_line": 411,
+ "line": "\n",
+ "lineno": 390,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 390,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 391,
+ "end_region_line": 411,
+ "line": " Parameters\n",
+ "lineno": 391,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 391,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 392,
+ "end_region_line": 411,
+ "line": " ----------\n",
+ "lineno": 392,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 392,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 393,
+ "end_region_line": 411,
+ "line": " i : List(float)\n",
+ "lineno": 393,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 393,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 394,
+ "end_region_line": 411,
+ "line": " Represents the first waypoint as a list, [time, pos, vel]\n",
+ "lineno": 394,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 394,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 395,
+ "end_region_line": 411,
+ "line": " f : List(float)\n",
+ "lineno": 395,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 395,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 396,
+ "end_region_line": 411,
+ "line": " Represents the second waypoint as a list, [time, pos, vel]\n",
+ "lineno": 396,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 396,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 397,
+ "end_region_line": 411,
+ "line": "\n",
+ "lineno": 397,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 397,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 398,
+ "end_region_line": 411,
+ "line": " Returns\n",
+ "lineno": 398,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 398,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 399,
+ "end_region_line": 411,
+ "line": " -------\n",
+ "lineno": 399,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 399,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 400,
+ "end_region_line": 411,
+ "line": " List(float)\n",
+ "lineno": 400,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 400,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 401,
+ "end_region_line": 411,
+ "line": " Represents a cubic polynomial as a coefficients + duration array [duration, a0, a1, a2, a3, 0, 0].\n",
+ "lineno": 401,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 401,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 402,
+ "end_region_line": 411,
+ "line": " The polynomial is f(t) = a0 + a1*t + a2*t^2 + a3*t^3\n",
+ "lineno": 402,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 402,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 403,
+ "end_region_line": 411,
+ "line": " \"\"\"\n",
+ "lineno": 403,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 403,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 404,
+ "end_region_line": 411,
+ "line": " i = [float(elem) for elem in i]\n",
+ "lineno": 404,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 404,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 405,
+ "end_region_line": 411,
+ "line": " f = [float(elem) for elem in f]\n",
+ "lineno": 405,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 405,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 406,
+ "end_region_line": 411,
+ "line": " duration = f[0] - i[0]\n",
+ "lineno": 406,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 406,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 407,
+ "end_region_line": 411,
+ "line": " a0 = i[1]\n",
+ "lineno": 407,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 407,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 408,
+ "end_region_line": 411,
+ "line": " a1 = i[2]\n",
+ "lineno": 408,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 408,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 409,
+ "end_region_line": 411,
+ "line": " a2 = (3 / duration ** 2) * (f[1] - i[1]) - (2 / duration) * i[2] - (1 / duration) * f[2]\n",
+ "lineno": 409,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 409,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 410,
+ "end_region_line": 411,
+ "line": " a3 = (-2 / duration ** 3) * (f[1] - i[1]) + (1 / duration ** 2) * (f[2] + i[2])\n",
+ "lineno": 410,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 410,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 411,
+ "end_region_line": 411,
+ "line": " return [duration, a0, a1, a2, a3, 0, 0]\n",
+ "lineno": 411,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 411,
+ "start_region_line": 388
+ },
+ {
+ "end_outermost_loop": 412,
+ "end_region_line": 412,
+ "line": "\n",
+ "lineno": 412,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 412,
+ "start_region_line": 412
+ },
+ {
+ "end_outermost_loop": 434,
+ "end_region_line": 434,
+ "line": "def generate_linear_polynomial(i, f):\n",
+ "lineno": 413,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 413,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 414,
+ "end_region_line": 434,
+ "line": " \"\"\"Generate linear polynomial from two points\n",
+ "lineno": 414,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 414,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 415,
+ "end_region_line": 434,
+ "line": "\n",
+ "lineno": 415,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 415,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 416,
+ "end_region_line": 434,
+ "line": " Parameters\n",
+ "lineno": 416,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 416,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 417,
+ "end_region_line": 434,
+ "line": " ----------\n",
+ "lineno": 417,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 417,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 418,
+ "end_region_line": 434,
+ "line": " i : List(float)\n",
+ "lineno": 418,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 418,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 419,
+ "end_region_line": 434,
+ "line": " Represents the first waypoint as a list, [time, pos]\n",
+ "lineno": 419,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 419,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 420,
+ "end_region_line": 434,
+ "line": " f : List(float)\n",
+ "lineno": 420,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 420,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 421,
+ "end_region_line": 434,
+ "line": " Represents the second waypoint as a list, [time, pos]\n",
+ "lineno": 421,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 421,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 422,
+ "end_region_line": 434,
+ "line": "\n",
+ "lineno": 422,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 422,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 423,
+ "end_region_line": 434,
+ "line": " Returns\n",
+ "lineno": 423,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 423,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 424,
+ "end_region_line": 434,
+ "line": " -------\n",
+ "lineno": 424,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 424,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 425,
+ "end_region_line": 434,
+ "line": " List(float)\n",
+ "lineno": 425,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 425,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 426,
+ "end_region_line": 434,
+ "line": " Represents a linear polynomial as a coefficients + duration array [duration, a0, a1, 0, 0, 0, 0].\n",
+ "lineno": 426,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 426,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 427,
+ "end_region_line": 434,
+ "line": " The polynomial is f(t) = a0 + a1*t\n",
+ "lineno": 427,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 427,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 428,
+ "end_region_line": 434,
+ "line": " \"\"\"\n",
+ "lineno": 428,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 428,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 429,
+ "end_region_line": 434,
+ "line": " i = [float(elem) for elem in i]\n",
+ "lineno": 429,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 429,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 430,
+ "end_region_line": 434,
+ "line": " f = [float(elem) for elem in f]\n",
+ "lineno": 430,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 430,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 431,
+ "end_region_line": 434,
+ "line": " duration = f[0] - i[0]\n",
+ "lineno": 431,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 431,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 432,
+ "end_region_line": 434,
+ "line": " a0 = i[1]\n",
+ "lineno": 432,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 432,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 433,
+ "end_region_line": 434,
+ "line": " a1 = (f[1] - i[1]) / duration\n",
+ "lineno": 433,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 433,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 434,
+ "end_region_line": 434,
+ "line": " return [duration, a0, a1, 0, 0, 0, 0]\n",
+ "lineno": 434,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 434,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 435,
+ "end_region_line": 435,
+ "line": "\n",
+ "lineno": 435,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 435,
+ "start_region_line": 435
+ },
+ {
+ "end_outermost_loop": 477,
+ "end_region_line": 477,
+ "line": "def get_pose_diff(pose0, pose1, translation_atol=2e-3, rotation_atol=2e-2):\n",
+ "lineno": 436,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 436,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 437,
+ "end_region_line": 477,
+ "line": " \"\"\"Return the motion required to get from pose 0 to pose 1.\n",
+ "lineno": 437,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 437,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 438,
+ "end_region_line": 477,
+ "line": "\n",
+ "lineno": 438,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 438,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 439,
+ "end_region_line": 477,
+ "line": " Assumed that between pose 0 and pose 1, there has only been\n",
+ "lineno": 439,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 439,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 440,
+ "end_region_line": 477,
+ "line": " either a translation or rotation motion.\n",
+ "lineno": 440,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 440,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 441,
+ "end_region_line": 477,
+ "line": "\n",
+ "lineno": 441,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 441,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 442,
+ "end_region_line": 477,
+ "line": " Parameters\n",
+ "lineno": 442,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 442,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 443,
+ "end_region_line": 477,
+ "line": " ----------\n",
+ "lineno": 443,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 443,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 444,
+ "end_region_line": 477,
+ "line": " pose0 : Tuple(float, float, float)\n",
+ "lineno": 444,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 444,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 445,
+ "end_region_line": 477,
+ "line": " x, y, theta in meters and radians\n",
+ "lineno": 445,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 445,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 446,
+ "end_region_line": 477,
+ "line": " pose1 : Tuple(float, float, float)\n",
+ "lineno": 446,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 446,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 447,
+ "end_region_line": 477,
+ "line": " x, y, theta in meters and radians\n",
+ "lineno": 447,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 447,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 448,
+ "end_region_line": 477,
+ "line": "\n",
+ "lineno": 448,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 448,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 449,
+ "end_region_line": 477,
+ "line": " Returns\n",
+ "lineno": 449,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 449,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 450,
+ "end_region_line": 477,
+ "line": " -------\n",
+ "lineno": 450,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 450,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 451,
+ "end_region_line": 477,
+ "line": " float, float\n",
+ "lineno": 451,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 451,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 452,
+ "end_region_line": 477,
+ "line": " Tuple (dx, dtheta) of translation and rotation required to\n",
+ "lineno": 452,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 452,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 453,
+ "end_region_line": 477,
+ "line": " move from pose0 to pose1\n",
+ "lineno": 453,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 453,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 454,
+ "end_region_line": 477,
+ "line": " \"\"\"\n",
+ "lineno": 454,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 454,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 455,
+ "end_region_line": 477,
+ "line": " x0, y0, theta0 = pose0\n",
+ "lineno": 455,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 455,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 456,
+ "end_region_line": 477,
+ "line": " x1, y1, theta1 = pose1\n",
+ "lineno": 456,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 456,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 457,
+ "end_region_line": 477,
+ "line": " theta0 = np.arctan2(np.sin(theta0), np.cos(theta0)) # constrains to [-pi, pi]\n",
+ "lineno": 457,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 457,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 458,
+ "end_region_line": 477,
+ "line": " theta1 = np.arctan2(np.sin(theta1), np.cos(theta1)) # constrains to [-pi, pi]\n",
+ "lineno": 458,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 458,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 459,
+ "end_region_line": 477,
+ "line": "\n",
+ "lineno": 459,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 459,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 477,
+ "end_region_line": 477,
+ "line": " # TODO: For now, we use a simplified motion model where we assume\n",
+ "lineno": 460,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 436,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 477,
+ "end_region_line": 477,
+ "line": " # that every motion is either a translation OR a rotation,\n",
+ "lineno": 461,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 436,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 477,
+ "end_region_line": 477,
+ "line": " # and the translation is either straight forward or straight back\n",
+ "lineno": 462,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 436,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 464,
+ "end_region_line": 477,
+ "line": " if np.isclose(x0, x1, atol=translation_atol) and np.isclose(y0, y1, atol=translation_atol):\n",
+ "lineno": 463,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 463,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 464,
+ "end_region_line": 477,
+ "line": " return 0.0, theta1 - theta0\n",
+ "lineno": 464,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 464,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 465,
+ "end_region_line": 477,
+ "line": "\n",
+ "lineno": 465,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 465,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 475,
+ "end_region_line": 477,
+ "line": " if np.isclose(theta0, theta1, atol=rotation_atol):\n",
+ "lineno": 466,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 466,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 467,
+ "end_region_line": 477,
+ "line": " dx = x1 - x0\n",
+ "lineno": 467,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 467,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 468,
+ "end_region_line": 477,
+ "line": " dy = y1 - y0\n",
+ "lineno": 468,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 468,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 469,
+ "end_region_line": 477,
+ "line": " drive_angle = math.atan2(dy, dx)\n",
+ "lineno": 469,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 469,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 470,
+ "end_region_line": 477,
+ "line": " distance = math.hypot(dy, dx)\n",
+ "lineno": 470,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 470,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 472,
+ "end_region_line": 477,
+ "line": " if np.isclose(drive_angle, theta0, atol=rotation_atol):\n",
+ "lineno": 471,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 471,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 472,
+ "end_region_line": 477,
+ "line": " return distance, 0.0\n",
+ "lineno": 472,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 472,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 473,
+ "end_region_line": 477,
+ "line": " opposite_theta0 = np.arctan2(np.sin(theta0 + np.pi), np.cos(theta0 + np.pi)) # constrains to [-pi, pi]\n",
+ "lineno": 473,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 473,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 475,
+ "end_region_line": 477,
+ "line": " if np.isclose(drive_angle, opposite_theta0, atol=rotation_atol):\n",
+ "lineno": 474,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 474,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 475,
+ "end_region_line": 477,
+ "line": " return -distance, 0.0\n",
+ "lineno": 475,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 475,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 476,
+ "end_region_line": 477,
+ "line": "\n",
+ "lineno": 476,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 476,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 477,
+ "end_region_line": 477,
+ "line": " return 0.0, 0.0\n",
+ "lineno": 477,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 477,
+ "start_region_line": 436
+ },
+ {
+ "end_outermost_loop": 478,
+ "end_region_line": 478,
+ "line": "\n",
+ "lineno": 478,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 478,
+ "start_region_line": 478
+ },
+ {
+ "end_outermost_loop": 486,
+ "end_region_line": 486,
+ "line": "def pseudo_N_to_effort_pct(joint_name,contact_thresh_N):\n",
+ "lineno": 479,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 479,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 480,
+ "end_region_line": 486,
+ "line": " import stretch_body.robot_params\n",
+ "lineno": 480,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 480,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 481,
+ "end_region_line": 486,
+ "line": " d = stretch_body.robot_params.RobotParams.get_params()[1] #Get complete param dict\n",
+ "lineno": 481,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 481,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 482,
+ "end_region_line": 486,
+ "line": " motor_name = {'arm':'hello-motor-arm', 'lift': 'hello-motor-lift', 'base':'hello-motor-left-wheel'}[joint_name]\n",
+ "lineno": 482,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 482,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 483,
+ "end_region_line": 486,
+ "line": " i_feedforward = 0 if joint_name =='base' else d[joint_name]['i_feedforward']\n",
+ "lineno": 483,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 483,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 484,
+ "end_region_line": 486,
+ "line": " iMax_name = 'iMax_neg' if contact_thresh_N\\u003c0 else 'iMax_pos'\n",
+ "lineno": 484,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 484,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 485,
+ "end_region_line": 486,
+ "line": " contact_A = (contact_thresh_N / d[joint_name]['force_N_per_A'])+i_feedforward\n",
+ "lineno": 485,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 485,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 486,
+ "end_region_line": 486,
+ "line": " return 100*contact_A / abs(d[motor_name]['gains'][iMax_name])\n",
+ "lineno": 486,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 486,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 487,
+ "end_region_line": 487,
+ "line": "\n",
+ "lineno": 487,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 487,
+ "start_region_line": 487
+ },
+ {
+ "end_outermost_loop": 488,
+ "end_region_line": 488,
+ "line": "\n",
+ "lineno": 488,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 488,
+ "start_region_line": 488
+ },
+ {
+ "end_outermost_loop": 513,
+ "end_region_line": 513,
+ "line": "def check_deprecated_contact_model_base(joint,method_name, contact_thresh_N,contact_thresh ):\n",
+ "lineno": 489,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 489,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 490,
+ "end_region_line": 513,
+ "line": " \"\"\"\n",
+ "lineno": 490,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 490,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 491,
+ "end_region_line": 513,
+ "line": " With RE2 we are transitioning entire stretch fleet to use new API (and effort_pct for the contact model)\n",
+ "lineno": 491,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 491,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 492,
+ "end_region_line": 513,
+ "line": " Catch older code that is using the older API and require updating of code\n",
+ "lineno": 492,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 492,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 493,
+ "end_region_line": 513,
+ "line": " \"\"\"\n",
+ "lineno": 493,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 493,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 494,
+ "end_region_line": 513,
+ "line": "\n",
+ "lineno": 494,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 494,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 513,
+ "end_region_line": 513,
+ "line": " #Check if old parameters still found in YAML\n",
+ "lineno": 495,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 489,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 503,
+ "end_region_line": 513,
+ "line": " if ('contact_thresh_max_N' in joint.params) or ('contact_thresh_N' in joint.params):\n",
+ "lineno": 496,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 496,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 497,
+ "end_region_line": 513,
+ "line": " msg=\"Robot is using out-of-date contact parameters\"\n",
+ "lineno": 497,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 497,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 498,
+ "end_region_line": 513,
+ "line": " msg=msg+'Please run tool RE1_migrate_contacts.py before continuing.\\n'\n",
+ "lineno": 498,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 498,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 499,
+ "end_region_line": 513,
+ "line": " msg=msg+'For more details, see https://forum.hello-robot.com/t/476 \\n'\n",
+ "lineno": 499,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 499,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 500,
+ "end_region_line": 513,
+ "line": " msg = msg + 'In method %s.%s' % (joint.name, method_name)\n",
+ "lineno": 500,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 500,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 501,
+ "end_region_line": 513,
+ "line": " print(msg)\n",
+ "lineno": 501,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 501,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 502,
+ "end_region_line": 513,
+ "line": " joint.logger.error(msg)\n",
+ "lineno": 502,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 502,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 503,
+ "end_region_line": 513,
+ "line": " sys.exit(1)\n",
+ "lineno": 503,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 503,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 504,
+ "end_region_line": 513,
+ "line": "\n",
+ "lineno": 504,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 504,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 513,
+ "end_region_line": 513,
+ "line": " #Check if code is passing in old values\n",
+ "lineno": 505,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 489,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 513,
+ "end_region_line": 513,
+ "line": " if contact_thresh_N is not None:\n",
+ "lineno": 506,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 506,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 507,
+ "end_region_line": 513,
+ "line": " msg='Use of parameter contact_thresh_N is no longer supported\\n'\n",
+ "lineno": 507,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 507,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 508,
+ "end_region_line": 513,
+ "line": " msg= msg + 'Update your code to use (contact_thresh)\\n'\n",
+ "lineno": 508,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 508,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 509,
+ "end_region_line": 513,
+ "line": " msg = msg + 'For more details, see https://forum.hello-robot.com/t/476\\n'\n",
+ "lineno": 509,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 509,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 510,
+ "end_region_line": 513,
+ "line": " msg=msg+'In method %s.%s'%(joint.name,method_name)\n",
+ "lineno": 510,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 510,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 511,
+ "end_region_line": 513,
+ "line": " print(msg)\n",
+ "lineno": 511,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 511,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 512,
+ "end_region_line": 513,
+ "line": " joint.logger.error(msg)\n",
+ "lineno": 512,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 512,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 513,
+ "end_region_line": 513,
+ "line": " sys.exit(1)\n",
+ "lineno": 513,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 513,
+ "start_region_line": 489
+ },
+ {
+ "end_outermost_loop": 514,
+ "end_region_line": 514,
+ "line": "\n",
+ "lineno": 514,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 514,
+ "start_region_line": 514
+ },
+ {
+ "end_outermost_loop": 558,
+ "end_region_line": 558,
+ "line": "def check_deprecated_contact_model_prismatic_joint(joint,method_name, contact_thresh_pos_N,contact_thresh_neg_N,contact_thresh_pos,contact_thresh_neg ):\n",
+ "lineno": 515,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 515,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 516,
+ "end_region_line": 558,
+ "line": " \"\"\"\n",
+ "lineno": 516,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 516,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 517,
+ "end_region_line": 558,
+ "line": " With RE2 we are transitioning entire stretch fleet to use new API (and effort_pct for the contact model)\n",
+ "lineno": 517,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 517,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 518,
+ "end_region_line": 558,
+ "line": " Catch older code that is using the older API and require updating of code\n",
+ "lineno": 518,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 518,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 519,
+ "end_region_line": 558,
+ "line": " For code that was, for example:\n",
+ "lineno": 519,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 519,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 520,
+ "end_region_line": 558,
+ "line": " arm.move_to(x_m=0.1, contact_thresh_pos_N=30.0, contact_thresh_neg_N=-30.0)\n",
+ "lineno": 520,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 520,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 521,
+ "end_region_line": 558,
+ "line": " Should now be:\n",
+ "lineno": 521,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 521,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 522,
+ "end_region_line": 558,
+ "line": " arm.move_to(x_m=0.1, contact_thresh_pos=pseudo_N_to_effort_pct(30.0),\n",
+ "lineno": 522,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 522,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 523,
+ "end_region_line": 558,
+ "line": " contact_thresh_neg=pseudo_N_to_effort_pct(-30.0))\n",
+ "lineno": 523,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 523,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 524,
+ "end_region_line": 558,
+ "line": " \"\"\"\n",
+ "lineno": 524,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 524,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 525,
+ "end_region_line": 558,
+ "line": "\n",
+ "lineno": 525,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 525,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 558,
+ "end_region_line": 558,
+ "line": " #Check if old parameters still found in YAML\n",
+ "lineno": 526,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 515,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 534,
+ "end_region_line": 558,
+ "line": " if ('contact_thresh_max_N' in joint.params) or ('contact_thresh_N' in joint.params) or ('homing_force_N' in joint.params):\n",
+ "lineno": 527,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 527,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 528,
+ "end_region_line": 558,
+ "line": " msg=\"Robot is using out-of-date contact parameters\\n\"\n",
+ "lineno": 528,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 528,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 529,
+ "end_region_line": 558,
+ "line": " msg=msg+'Please run tool RE1_migrate_contacts.py before continuing.\\n'\n",
+ "lineno": 529,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 529,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 530,
+ "end_region_line": 558,
+ "line": " msg=msg+'For more details, see https://forum.hello-robot.com/t/476 \\n'\n",
+ "lineno": 530,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 530,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 531,
+ "end_region_line": 558,
+ "line": " msg = msg + 'In method %s.%s' % (joint.name, method_name)\n",
+ "lineno": 531,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 531,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 532,
+ "end_region_line": 558,
+ "line": " print(msg)\n",
+ "lineno": 532,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 532,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 533,
+ "end_region_line": 558,
+ "line": " joint.logger.error(msg)\n",
+ "lineno": 533,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 533,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 534,
+ "end_region_line": 558,
+ "line": " sys.exit(1)\n",
+ "lineno": 534,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 534,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 535,
+ "end_region_line": 558,
+ "line": "\n",
+ "lineno": 535,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 535,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 558,
+ "end_region_line": 558,
+ "line": " #Check if code is passing in old values\n",
+ "lineno": 536,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 515,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 544,
+ "end_region_line": 558,
+ "line": " if contact_thresh_pos_N is not None or contact_thresh_neg_N is not None:\n",
+ "lineno": 537,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 537,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 538,
+ "end_region_line": 558,
+ "line": " msg='Use of parameters contact_thresh_pos_N and contact_thresh_neg_N is no longer supported\\n'\n",
+ "lineno": 538,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 538,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 539,
+ "end_region_line": 558,
+ "line": " msg= msg + 'Update your code to use (contact_thresh_pos, contact_thresh_neg)\\n'\n",
+ "lineno": 539,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 539,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 540,
+ "end_region_line": 558,
+ "line": " msg = msg + 'For more details, see https://forum.hello-robot.com/t/476\\n'\n",
+ "lineno": 540,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 540,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 541,
+ "end_region_line": 558,
+ "line": " msg=msg+'In method %s.%s'%(joint.name,method_name)\n",
+ "lineno": 541,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 541,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 542,
+ "end_region_line": 558,
+ "line": " print(msg)\n",
+ "lineno": 542,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 542,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 543,
+ "end_region_line": 558,
+ "line": " joint.logger.error(msg)\n",
+ "lineno": 543,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 543,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 544,
+ "end_region_line": 558,
+ "line": " sys.exit(1)\n",
+ "lineno": 544,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 544,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 545,
+ "end_region_line": 558,
+ "line": "\n",
+ "lineno": 545,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 545,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 558,
+ "end_region_line": 558,
+ "line": " #Check if code is passing in new values but not yet migrated\n",
+ "lineno": 546,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 515,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 558,
+ "end_region_line": 558,
+ "line": " if contact_thresh_pos is not None or contact_thresh_neg is not None \\\n",
+ "lineno": 547,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 547,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 558,
+ "end_region_line": 558,
+ "line": " or (contact_thresh_pos is None and contact_thresh_neg is None):\n",
+ "lineno": 548,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 547,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 558,
+ "end_region_line": 558,
+ "line": " if ('contact_models' not in joint.params) or ('effort_pct' not in joint.params['contact_models']) or\\\n",
+ "lineno": 549,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 549,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 558,
+ "end_region_line": 558,
+ "line": " ('contact_thresh_default' not in joint.params['contact_models']['effort_pct']) or\\\n",
+ "lineno": 550,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 549,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 558,
+ "end_region_line": 558,
+ "line": " ('contact_thresh_homing' not in joint.params['contact_models']['effort_pct']) :\n",
+ "lineno": 551,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 549,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 552,
+ "end_region_line": 558,
+ "line": " msg='Effort_Pct contact parameters not available\\n'\n",
+ "lineno": 552,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 552,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 553,
+ "end_region_line": 558,
+ "line": " msg = msg + 'Please run tool RE1_migrate_contacts.py before continuing.\\n'\n",
+ "lineno": 553,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 553,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 554,
+ "end_region_line": 558,
+ "line": " msg = msg + 'For more details, see https://forum.hello-robot.com/t/476 \\n'\n",
+ "lineno": 554,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 554,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 555,
+ "end_region_line": 558,
+ "line": " msg=msg+'In method %s.%s'%(joint.name,method_name)\n",
+ "lineno": 555,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 555,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 556,
+ "end_region_line": 558,
+ "line": " print(msg)\n",
+ "lineno": 556,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 556,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 557,
+ "end_region_line": 558,
+ "line": " joint.logger.error(msg)\n",
+ "lineno": 557,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 557,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 558,
+ "end_region_line": 558,
+ "line": " sys.exit(1)\n",
+ "lineno": 558,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 558,
+ "start_region_line": 515
+ },
+ {
+ "end_outermost_loop": 559,
+ "end_region_line": 559,
+ "line": "\n",
+ "lineno": 559,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 559,
+ "start_region_line": 559
+ },
+ {
+ "end_outermost_loop": 565,
+ "end_region_line": 565,
+ "line": "def check_file_exists(fn):\n",
+ "lineno": 560,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 560,
+ "start_region_line": 560
+ },
+ {
+ "end_outermost_loop": 565,
+ "end_region_line": 565,
+ "line": " if os.path.exists(fn):\n",
+ "lineno": 561,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 561,
+ "start_region_line": 560
+ },
+ {
+ "end_outermost_loop": 562,
+ "end_region_line": 565,
+ "line": " return True\n",
+ "lineno": 562,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 562,
+ "start_region_line": 560
+ },
+ {
+ "end_outermost_loop": 565,
+ "end_region_line": 565,
+ "line": " else:\n",
+ "lineno": 563,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 561,
+ "start_region_line": 560
+ },
+ {
+ "end_outermost_loop": 564,
+ "end_region_line": 565,
+ "line": " print(f\"Unable to find file: {fn}\")\n",
+ "lineno": 564,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 564,
+ "start_region_line": 560
+ },
+ {
+ "end_outermost_loop": 565,
+ "end_region_line": 565,
+ "line": " return False\n",
+ "lineno": 565,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 565,
+ "start_region_line": 560
+ },
+ {
+ "end_outermost_loop": 566,
+ "end_region_line": 566,
+ "line": "\n",
+ "lineno": 566,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 566,
+ "start_region_line": 566
+ },
+ {
+ "end_outermost_loop": 571,
+ "end_region_line": 571,
+ "line": "def to_parabola_transform(x):\n",
+ "lineno": 567,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 567,
+ "start_region_line": 567
+ },
+ {
+ "end_outermost_loop": 571,
+ "end_region_line": 571,
+ "line": " if x\\u003c0:\n",
+ "lineno": 568,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 568,
+ "start_region_line": 567
+ },
+ {
+ "end_outermost_loop": 569,
+ "end_region_line": 571,
+ "line": " return -1*(abs(x)**2)\n",
+ "lineno": 569,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 569,
+ "start_region_line": 567
+ },
+ {
+ "end_outermost_loop": 571,
+ "end_region_line": 571,
+ "line": " else:\n",
+ "lineno": 570,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 568,
+ "start_region_line": 567
+ },
+ {
+ "end_outermost_loop": 571,
+ "end_region_line": 571,
+ "line": " return x**2\n",
+ "lineno": 571,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 571,
+ "start_region_line": 567
+ },
+ {
+ "end_outermost_loop": 572,
+ "end_region_line": 572,
+ "line": "\n",
+ "lineno": 572,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 572,
+ "start_region_line": 572
+ },
+ {
+ "end_outermost_loop": 577,
+ "end_region_line": 577,
+ "line": "def map_to_range(value, new_min, new_max):\n",
+ "lineno": 573,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 573,
+ "start_region_line": 573
+ },
+ {
+ "end_outermost_loop": 577,
+ "end_region_line": 577,
+ "line": " # Ensure value is between 0 and 1\n",
+ "lineno": 574,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 573,
+ "start_region_line": 573
+ },
+ {
+ "end_outermost_loop": 575,
+ "end_region_line": 577,
+ "line": " value = max(0, min(1, value))\n",
+ "lineno": 575,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 575,
+ "start_region_line": 573
+ },
+ {
+ "end_outermost_loop": 576,
+ "end_region_line": 577,
+ "line": " mapped_value = (value - 0) * (new_max - new_min) / (1 - 0) + new_min\n",
+ "lineno": 576,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 576,
+ "start_region_line": 573
+ },
+ {
+ "end_outermost_loop": 577,
+ "end_region_line": 577,
+ "line": " return mapped_value\n",
+ "lineno": 577,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 577,
+ "start_region_line": 573
+ },
+ {
+ "end_outermost_loop": 578,
+ "end_region_line": 578,
+ "line": "\n",
+ "lineno": 578,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 578,
+ "start_region_line": 578
+ },
+ {
+ "end_outermost_loop": 603,
+ "end_region_line": 603,
+ "line": "def get_video_devices():\n",
+ "lineno": 579,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 579,
+ "start_region_line": 579
+ },
+ {
+ "end_outermost_loop": 580,
+ "end_region_line": 603,
+ "line": " \"\"\"\n",
+ "lineno": 580,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 580,
+ "start_region_line": 579
+ },
+ {
+ "end_outermost_loop": 581,
+ "end_region_line": 603,
+ "line": " Returns dictionary of all the enumerated video devices found in the robot \n",
+ "lineno": 581,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 581,
+ "start_region_line": 579
+ },
+ {
+ "end_outermost_loop": 582,
+ "end_region_line": 603,
+ "line": " \"\"\"\n",
+ "lineno": 582,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 582,
+ "start_region_line": 579
+ },
+ {
+ "end_outermost_loop": 583,
+ "end_region_line": 603,
+ "line": " command = 'v4l2-ctl --list-devices'\n",
+ "lineno": 583,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 583,
+ "start_region_line": 579
+ },
+ {
+ "end_outermost_loop": 584,
+ "end_region_line": 603,
+ "line": " lines = subprocess.getoutput(command).split('\\n')\n",
+ "lineno": 584,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 584,
+ "start_region_line": 579
+ },
+ {
+ "end_outermost_loop": 585,
+ "end_region_line": 603,
+ "line": " lines = [l.strip() for l in lines if l != '']\n",
+ "lineno": 585,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 585,
+ "start_region_line": 579
+ },
+ {
+ "end_outermost_loop": 586,
+ "end_region_line": 603,
+ "line": " cameras = [l for l in lines if not ('/dev/' in l)]\n",
+ "lineno": 586,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 586,
+ "start_region_line": 579
+ },
+ {
+ "end_outermost_loop": 587,
+ "end_region_line": 603,
+ "line": " devices = [l for l in lines if '/dev/' in l]\n",
+ "lineno": 587,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 587,
+ "start_region_line": 579
+ },
+ {
+ "end_outermost_loop": 588,
+ "end_region_line": 603,
+ "line": "\n",
+ "lineno": 588,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 588,
+ "start_region_line": 579
+ },
+ {
+ "end_outermost_loop": 589,
+ "end_region_line": 603,
+ "line": " all_camera_devices = {}\n",
+ "lineno": 589,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 589,
+ "start_region_line": 579
+ },
+ {
+ "end_outermost_loop": 590,
+ "end_region_line": 603,
+ "line": " camera_devices = []\n",
+ "lineno": 590,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 590,
+ "start_region_line": 579
+ },
+ {
+ "end_outermost_loop": 591,
+ "end_region_line": 603,
+ "line": " current_camera = None\n",
+ "lineno": 591,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 591,
+ "start_region_line": 579
+ },
+ {
+ "end_outermost_loop": 599,
+ "end_region_line": 599,
+ "line": " for line in lines:\n",
+ "lineno": 592,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 592,
+ "start_region_line": 592
+ },
+ {
+ "end_outermost_loop": 599,
+ "end_region_line": 599,
+ "line": " if line in cameras:\n",
+ "lineno": 593,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 592,
+ "start_region_line": 592
+ },
+ {
+ "end_outermost_loop": 599,
+ "end_region_line": 599,
+ "line": " if (current_camera is not None) and camera_devices:\n",
+ "lineno": 594,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 592,
+ "start_region_line": 592
+ },
+ {
+ "end_outermost_loop": 599,
+ "end_region_line": 599,
+ "line": " all_camera_devices[current_camera] = camera_devices\n",
+ "lineno": 595,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 592,
+ "start_region_line": 592
+ },
+ {
+ "end_outermost_loop": 599,
+ "end_region_line": 599,
+ "line": " camera_devices = []\n",
+ "lineno": 596,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 592,
+ "start_region_line": 592
+ },
+ {
+ "end_outermost_loop": 599,
+ "end_region_line": 599,
+ "line": " current_camera = line\n",
+ "lineno": 597,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 592,
+ "start_region_line": 592
+ },
+ {
+ "end_outermost_loop": 599,
+ "end_region_line": 599,
+ "line": " elif line in devices:\n",
+ "lineno": 598,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 592,
+ "start_region_line": 592
+ },
+ {
+ "end_outermost_loop": 599,
+ "end_region_line": 599,
+ "line": " camera_devices.append(line)\n",
+ "lineno": 599,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 592,
+ "start_region_line": 592
+ },
+ {
+ "end_outermost_loop": 601,
+ "end_region_line": 603,
+ "line": " if (current_camera is not None) and camera_devices:\n",
+ "lineno": 600,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 600,
+ "start_region_line": 579
+ },
+ {
+ "end_outermost_loop": 601,
+ "end_region_line": 603,
+ "line": " all_camera_devices[current_camera] = camera_devices\n",
+ "lineno": 601,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 601,
+ "start_region_line": 579
+ },
+ {
+ "end_outermost_loop": 602,
+ "end_region_line": 603,
+ "line": "\n",
+ "lineno": 602,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 602,
+ "start_region_line": 579
+ },
+ {
+ "end_outermost_loop": 603,
+ "end_region_line": 603,
+ "line": " return all_camera_devices\n",
+ "lineno": 603,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 603,
+ "start_region_line": 579
+ },
+ {
+ "end_outermost_loop": 604,
+ "end_region_line": 604,
+ "line": "\n",
+ "lineno": 604,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 604,
+ "start_region_line": 604
+ },
+ {
+ "end_outermost_loop": 619,
+ "end_region_line": 619,
+ "line": "def setup_realsense_camera(serial_number, color_size, depth_size, fps):\n",
+ "lineno": 605,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 605,
+ "start_region_line": 605
+ },
+ {
+ "end_outermost_loop": 606,
+ "end_region_line": 619,
+ "line": " \"\"\"\n",
+ "lineno": 606,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 606,
+ "start_region_line": 605
+ },
+ {
+ "end_outermost_loop": 607,
+ "end_region_line": 619,
+ "line": " Returns a Realsense camera pipeline used for accessing D435i \\u0026 D405's video streams\n",
+ "lineno": 607,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 607,
+ "start_region_line": 605
+ },
+ {
+ "end_outermost_loop": 608,
+ "end_region_line": 619,
+ "line": " \"\"\"\n",
+ "lineno": 608,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 608,
+ "start_region_line": 605
+ },
+ {
+ "end_outermost_loop": 609,
+ "end_region_line": 619,
+ "line": " pipeline = rs.pipeline()\n",
+ "lineno": 609,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 609,
+ "start_region_line": 605
+ },
+ {
+ "end_outermost_loop": 610,
+ "end_region_line": 619,
+ "line": " config = rs.config()\n",
+ "lineno": 610,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 610,
+ "start_region_line": 605
+ },
+ {
+ "end_outermost_loop": 611,
+ "end_region_line": 619,
+ "line": "\n",
+ "lineno": 611,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 611,
+ "start_region_line": 605
+ },
+ {
+ "end_outermost_loop": 613,
+ "end_region_line": 619,
+ "line": " if serial_number:\n",
+ "lineno": 612,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 612,
+ "start_region_line": 605
+ },
+ {
+ "end_outermost_loop": 613,
+ "end_region_line": 619,
+ "line": " config.enable_device(serial_number)\n",
+ "lineno": 613,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 613,
+ "start_region_line": 605
+ },
+ {
+ "end_outermost_loop": 614,
+ "end_region_line": 619,
+ "line": "\n",
+ "lineno": 614,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 614,
+ "start_region_line": 605
+ },
+ {
+ "end_outermost_loop": 615,
+ "end_region_line": 619,
+ "line": " config.enable_stream(rs.stream.color, color_size[0], color_size[1], rs.format.bgr8, fps)\n",
+ "lineno": 615,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 615,
+ "start_region_line": 605
+ },
+ {
+ "end_outermost_loop": 616,
+ "end_region_line": 619,
+ "line": " config.enable_stream(rs.stream.depth, depth_size[0], depth_size[1], rs.format.z16, fps)\n",
+ "lineno": 616,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 616,
+ "start_region_line": 605
+ },
+ {
+ "end_outermost_loop": 617,
+ "end_region_line": 619,
+ "line": "\n",
+ "lineno": 617,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 617,
+ "start_region_line": 605
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 619,
+ "line": " profile = pipeline.start(config)\n",
+ "lineno": 618,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 618,
+ "start_region_line": 605
+ },
+ {
+ "end_outermost_loop": 619,
+ "end_region_line": 619,
+ "line": " return pipeline\n",
+ "lineno": 619,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 619,
+ "start_region_line": 605
+ },
+ {
+ "end_outermost_loop": 620,
+ "end_region_line": 620,
+ "line": "\n",
+ "lineno": 620,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 620,
+ "start_region_line": 620
+ },
+ {
+ "end_outermost_loop": 634,
+ "end_region_line": 634,
+ "line": "def setup_uvc_camera(device_index, size=None, fps=None, format = None):\n",
+ "lineno": 621,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 621,
+ "start_region_line": 621
+ },
+ {
+ "end_outermost_loop": 622,
+ "end_region_line": 634,
+ "line": " \"\"\"\n",
+ "lineno": 622,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 622,
+ "start_region_line": 621
+ },
+ {
+ "end_outermost_loop": 623,
+ "end_region_line": 634,
+ "line": " Returns Opencv capture object of the UVC video divice\n",
+ "lineno": 623,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 623,
+ "start_region_line": 621
+ },
+ {
+ "end_outermost_loop": 624,
+ "end_region_line": 634,
+ "line": " \"\"\"\n",
+ "lineno": 624,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 624,
+ "start_region_line": 621
+ },
+ {
+ "end_outermost_loop": 625,
+ "end_region_line": 634,
+ "line": " cap = cv2.VideoCapture(device_index)\n",
+ "lineno": 625,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 625,
+ "start_region_line": 621
+ },
+ {
+ "end_outermost_loop": 628,
+ "end_region_line": 634,
+ "line": " if format:\n",
+ "lineno": 626,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 626,
+ "start_region_line": 621
+ },
+ {
+ "end_outermost_loop": 627,
+ "end_region_line": 634,
+ "line": " fourcc_value = cv2.VideoWriter_fourcc(*f'{format}')\n",
+ "lineno": 627,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 627,
+ "start_region_line": 621
+ },
+ {
+ "end_outermost_loop": 628,
+ "end_region_line": 634,
+ "line": " cap.set(cv2.CAP_PROP_FOURCC, fourcc_value)\n",
+ "lineno": 628,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 628,
+ "start_region_line": 621
+ },
+ {
+ "end_outermost_loop": 631,
+ "end_region_line": 634,
+ "line": " if size:\n",
+ "lineno": 629,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 629,
+ "start_region_line": 621
+ },
+ {
+ "end_outermost_loop": 630,
+ "end_region_line": 634,
+ "line": " cap.set(cv2.CAP_PROP_FRAME_WIDTH, size[0])\n",
+ "lineno": 630,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 630,
+ "start_region_line": 621
+ },
+ {
+ "end_outermost_loop": 631,
+ "end_region_line": 634,
+ "line": " cap.set(cv2.CAP_PROP_FRAME_HEIGHT, size[1])\n",
+ "lineno": 631,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 631,
+ "start_region_line": 621
+ },
+ {
+ "end_outermost_loop": 633,
+ "end_region_line": 634,
+ "line": " if fps:\n",
+ "lineno": 632,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 632,
+ "start_region_line": 621
+ },
+ {
+ "end_outermost_loop": 633,
+ "end_region_line": 634,
+ "line": " cap.set(cv2.CAP_PROP_FPS, fps)\n",
+ "lineno": 633,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 633,
+ "start_region_line": 621
+ },
+ {
+ "end_outermost_loop": 634,
+ "end_region_line": 634,
+ "line": " return cap\n",
+ "lineno": 634,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 634,
+ "start_region_line": 621
+ },
+ {
+ "end_outermost_loop": 635,
+ "end_region_line": 635,
+ "line": "\n",
+ "lineno": 635,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 635,
+ "start_region_line": 635
+ },
+ {
+ "end_outermost_loop": 648,
+ "end_region_line": 648,
+ "line": "def get_video_device_port(camera_name):\n",
+ "lineno": 636,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 636,
+ "start_region_line": 636
+ },
+ {
+ "end_outermost_loop": 637,
+ "end_region_line": 648,
+ "line": " \"\"\"\n",
+ "lineno": 637,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 637,
+ "start_region_line": 636
+ },
+ {
+ "end_outermost_loop": 638,
+ "end_region_line": 648,
+ "line": " Returns the video device port based on the given camera name match\n",
+ "lineno": 638,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 638,
+ "start_region_line": 636
+ },
+ {
+ "end_outermost_loop": 639,
+ "end_region_line": 648,
+ "line": " \"\"\"\n",
+ "lineno": 639,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 639,
+ "start_region_line": 636
+ },
+ {
+ "end_outermost_loop": 640,
+ "end_region_line": 648,
+ "line": " camera_devices = get_video_devices()\n",
+ "lineno": 640,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 640,
+ "start_region_line": 636
+ },
+ {
+ "end_outermost_loop": 641,
+ "end_region_line": 648,
+ "line": " camera_device = None\n",
+ "lineno": 641,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 641,
+ "start_region_line": 636
+ },
+ {
+ "end_outermost_loop": 646,
+ "end_region_line": 646,
+ "line": " for k,v in camera_devices.items():\n",
+ "lineno": 642,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 642,
+ "start_region_line": 642
+ },
+ {
+ "end_outermost_loop": 646,
+ "end_region_line": 646,
+ "line": " if camera_name in k:\n",
+ "lineno": 643,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 642,
+ "start_region_line": 642
+ },
+ {
+ "end_outermost_loop": 646,
+ "end_region_line": 646,
+ "line": " camera_device = v[0]\n",
+ "lineno": 644,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 642,
+ "start_region_line": 642
+ },
+ {
+ "end_outermost_loop": 646,
+ "end_region_line": 646,
+ "line": " print(f\"Found Camera={k} at port={camera_device} \")\n",
+ "lineno": 645,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 642,
+ "start_region_line": 642
+ },
+ {
+ "end_outermost_loop": 646,
+ "end_region_line": 646,
+ "line": " return camera_device\n",
+ "lineno": 646,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 642,
+ "start_region_line": 642
+ },
+ {
+ "end_outermost_loop": 647,
+ "end_region_line": 648,
+ "line": " print('ERROR: Did not find the specified camera_name = ' + str(camera_name))\n",
+ "lineno": 647,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 647,
+ "start_region_line": 636
+ },
+ {
+ "end_outermost_loop": 648,
+ "end_region_line": 648,
+ "line": " return camera_device",
+ "lineno": 648,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 648,
+ "start_region_line": 636
+ }
+ ],
+ "percent_cpu_time": 0.0
+ },
+ "/home/hello-robot/repos/stretch_body/body/stretch_body/robot_collision.py": {
+ "functions": [],
+ "imports": [
+ "import numpy as np",
+ "import time",
+ "import threading",
+ "import chime",
+ "import random",
+ "import signal"
+ ],
+ "leaks": {},
+ "lines": [
+ {
+ "end_outermost_loop": 1,
+ "end_region_line": 1,
+ "line": "#! /usr/bin/env python\n",
+ "lineno": 1,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1,
+ "start_region_line": 1
+ },
+ {
+ "end_outermost_loop": 2,
+ "end_region_line": 2,
+ "line": "\n",
+ "lineno": 2,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 2,
+ "start_region_line": 2
+ },
+ {
+ "end_outermost_loop": 3,
+ "end_region_line": 3,
+ "line": "from stretch_body.device import Device\n",
+ "lineno": 3,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 3,
+ "start_region_line": 3
+ },
+ {
+ "end_outermost_loop": 4,
+ "end_region_line": 4,
+ "line": "import urchin as urdf_loader\n",
+ "lineno": 4,
+ "memory_samples": [
+ [
+ 889626981,
+ 20.2229585647583
+ ],
+ [
+ 1035184185,
+ 30.317264556884766
+ ],
+ [
+ 1238993851,
+ 40.41176986694336
+ ]
+ ],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 460.97560396455555,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 30.000483512878418,
+ "n_malloc_mb": 30.000483512878418,
+ "n_mallocs": 0,
+ "n_peak_mb": 30.000483512878418,
+ "n_python_fraction": 0.986854335005924,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.599563241008711,
+ "start_outermost_loop": 4,
+ "start_region_line": 4
+ },
+ {
+ "end_outermost_loop": 5,
+ "end_region_line": 5,
+ "line": "import meshio\n",
+ "lineno": 5,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 5,
+ "start_region_line": 5
+ },
+ {
+ "end_outermost_loop": 6,
+ "end_region_line": 6,
+ "line": "import numpy as np\n",
+ "lineno": 6,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 6,
+ "start_region_line": 6
+ },
+ {
+ "end_outermost_loop": 7,
+ "end_region_line": 7,
+ "line": "import time\n",
+ "lineno": 7,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 7,
+ "start_region_line": 7
+ },
+ {
+ "end_outermost_loop": 8,
+ "end_region_line": 8,
+ "line": "import threading\n",
+ "lineno": 8,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 8,
+ "start_region_line": 8
+ },
+ {
+ "end_outermost_loop": 9,
+ "end_region_line": 9,
+ "line": "import chime\n",
+ "lineno": 9,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 9,
+ "start_region_line": 9
+ },
+ {
+ "end_outermost_loop": 10,
+ "end_region_line": 10,
+ "line": "import random\n",
+ "lineno": 10,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 10,
+ "start_region_line": 10
+ },
+ {
+ "end_outermost_loop": 11,
+ "end_region_line": 11,
+ "line": "from stretch_body.robot_params import RobotParams\n",
+ "lineno": 11,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 11,
+ "start_region_line": 11
+ },
+ {
+ "end_outermost_loop": 12,
+ "end_region_line": 12,
+ "line": "import multiprocessing\n",
+ "lineno": 12,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 12,
+ "start_region_line": 12
+ },
+ {
+ "end_outermost_loop": 13,
+ "end_region_line": 13,
+ "line": "import signal\n",
+ "lineno": 13,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 13,
+ "start_region_line": 13
+ },
+ {
+ "end_outermost_loop": 14,
+ "end_region_line": 14,
+ "line": "import ctypes\n",
+ "lineno": 14,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 14,
+ "start_region_line": 14
+ },
+ {
+ "end_outermost_loop": 15,
+ "end_region_line": 15,
+ "line": "\n",
+ "lineno": 15,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 15,
+ "start_region_line": 15
+ },
+ {
+ "end_outermost_loop": 16,
+ "end_region_line": 16,
+ "line": "try:\n",
+ "lineno": 16,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 16,
+ "start_region_line": 16
+ },
+ {
+ "end_outermost_loop": 17,
+ "end_region_line": 17,
+ "line": " # works on ubunut 22.04\n",
+ "lineno": 17,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 17,
+ "start_region_line": 17
+ },
+ {
+ "end_outermost_loop": 18,
+ "end_region_line": 18,
+ "line": " import importlib.resources as importlib_resources\n",
+ "lineno": 18,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 18,
+ "start_region_line": 18
+ },
+ {
+ "end_outermost_loop": 19,
+ "end_region_line": 19,
+ "line": " str(importlib_resources.files(\"stretch_body\"))\n",
+ "lineno": 19,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 19,
+ "start_region_line": 19
+ },
+ {
+ "end_outermost_loop": 20,
+ "end_region_line": 20,
+ "line": "except AttributeError as e:\n",
+ "lineno": 20,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 20,
+ "start_region_line": 20
+ },
+ {
+ "end_outermost_loop": 21,
+ "end_region_line": 21,
+ "line": " # works on ubuntu 20.04\n",
+ "lineno": 21,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 21,
+ "start_region_line": 21
+ },
+ {
+ "end_outermost_loop": 22,
+ "end_region_line": 22,
+ "line": " import importlib_resources\n",
+ "lineno": 22,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 22,
+ "start_region_line": 22
+ },
+ {
+ "end_outermost_loop": 23,
+ "end_region_line": 23,
+ "line": " str(importlib_resources.files(\"stretch_body\"))\n",
+ "lineno": 23,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 23,
+ "start_region_line": 23
+ },
+ {
+ "end_outermost_loop": 24,
+ "end_region_line": 24,
+ "line": "\n",
+ "lineno": 24,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 24,
+ "start_region_line": 24
+ },
+ {
+ "end_outermost_loop": 25,
+ "end_region_line": 25,
+ "line": "# #######################################################################\n",
+ "lineno": 25,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 25,
+ "start_region_line": 25
+ },
+ {
+ "end_outermost_loop": 26,
+ "end_region_line": 26,
+ "line": "\n",
+ "lineno": 26,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 26,
+ "start_region_line": 26
+ },
+ {
+ "end_outermost_loop": 62,
+ "end_region_line": 62,
+ "line": "def line_box_sat_intersection(line_point1, line_point2, aabb_min, aabb_max):\n",
+ "lineno": 27,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 27,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 28,
+ "end_region_line": 62,
+ "line": " \"\"\"\n",
+ "lineno": 28,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 28,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 29,
+ "end_region_line": 62,
+ "line": " Checks if a line segment intersects an AABB using the Separating Axis Theorem (SAT).\n",
+ "lineno": 29,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 29,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 30,
+ "end_region_line": 62,
+ "line": "\n",
+ "lineno": 30,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 30,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 31,
+ "end_region_line": 62,
+ "line": " Args:\n",
+ "lineno": 31,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 31,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 32,
+ "end_region_line": 62,
+ "line": " line_point1: np.array of shape (3,). First point of the line segment.\n",
+ "lineno": 32,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 32,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 33,
+ "end_region_line": 62,
+ "line": " line_point2: np.array of shape (3,). Second point of the line segment.\n",
+ "lineno": 33,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 33,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 34,
+ "end_region_line": 62,
+ "line": " aabb_min: np.array of shape (3,). Minimum corner of the AABB.\n",
+ "lineno": 34,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 34,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 35,
+ "end_region_line": 62,
+ "line": " aabb_max: np.array of shape (3,). Maximum corner of the AABB.\n",
+ "lineno": 35,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 35,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 36,
+ "end_region_line": 62,
+ "line": "\n",
+ "lineno": 36,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 36,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 37,
+ "end_region_line": 62,
+ "line": " Returns:\n",
+ "lineno": 37,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 37,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 38,
+ "end_region_line": 62,
+ "line": " bool: True if the line intersects the AABB, False otherwise.\n",
+ "lineno": 38,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 38,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 39,
+ "end_region_line": 62,
+ "line": " \"\"\"\n",
+ "lineno": 39,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 39,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 40,
+ "end_region_line": 62,
+ "line": "\n",
+ "lineno": 40,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 40,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 41,
+ "end_region_line": 62,
+ "line": " line_dir = line_point2 - line_point1\n",
+ "lineno": 41,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 41,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 42,
+ "end_region_line": 62,
+ "line": "\n",
+ "lineno": 42,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 42,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 62,
+ "end_region_line": 62,
+ "line": " # Check separating axes along AABB's edges\n",
+ "lineno": 43,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 27,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 51,
+ "end_region_line": 51,
+ "line": " for i in range(3):\n",
+ "lineno": 44,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 44,
+ "start_region_line": 44
+ },
+ {
+ "end_outermost_loop": 51,
+ "end_region_line": 51,
+ "line": " # Project line segment onto axis\n",
+ "lineno": 45,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 44,
+ "start_region_line": 44
+ },
+ {
+ "end_outermost_loop": 51,
+ "end_region_line": 51,
+ "line": " line_proj = np.dot(line_point1, np.eye(3)[i]) + np.dot(line_dir, np.eye(3)[i])\n",
+ "lineno": 46,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 44,
+ "start_region_line": 44
+ },
+ {
+ "end_outermost_loop": 51,
+ "end_region_line": 51,
+ "line": " aabb_proj = np.array([aabb_min[i], aabb_max[i]])\n",
+ "lineno": 47,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 44,
+ "start_region_line": 44
+ },
+ {
+ "end_outermost_loop": 51,
+ "end_region_line": 51,
+ "line": "\n",
+ "lineno": 48,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 44,
+ "start_region_line": 44
+ },
+ {
+ "end_outermost_loop": 51,
+ "end_region_line": 51,
+ "line": " # Check for overlap\n",
+ "lineno": 49,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 44,
+ "start_region_line": 44
+ },
+ {
+ "end_outermost_loop": 51,
+ "end_region_line": 51,
+ "line": " if not (np.min(line_proj) \\u003c= np.max(aabb_proj) and np.max(line_proj) \\u003e= np.min(aabb_proj)):\n",
+ "lineno": 50,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 44,
+ "start_region_line": 44
+ },
+ {
+ "end_outermost_loop": 51,
+ "end_region_line": 51,
+ "line": " return False # No overlap on this axis\n",
+ "lineno": 51,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 44,
+ "start_region_line": 44
+ },
+ {
+ "end_outermost_loop": 52,
+ "end_region_line": 62,
+ "line": "\n",
+ "lineno": 52,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 52,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 62,
+ "end_region_line": 62,
+ "line": " # Check separating axes along line direction\n",
+ "lineno": 53,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 27,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 54,
+ "end_region_line": 62,
+ "line": " line_axis = line_dir / np.linalg.norm(line_dir)\n",
+ "lineno": 54,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 54,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 55,
+ "end_region_line": 62,
+ "line": " aabb_proj = np.dot(aabb_min, line_axis), np.dot(aabb_max, line_axis)\n",
+ "lineno": 55,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 55,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 56,
+ "end_region_line": 62,
+ "line": " line_proj = np.dot(line_point1, line_axis), np.dot(line_point1 + line_dir, line_axis)\n",
+ "lineno": 56,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 56,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 57,
+ "end_region_line": 62,
+ "line": "\n",
+ "lineno": 57,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 57,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 62,
+ "end_region_line": 62,
+ "line": " # Check for overlap\n",
+ "lineno": 58,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 27,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 60,
+ "end_region_line": 62,
+ "line": " if not (np.min(line_proj) \\u003c= np.max(aabb_proj) and np.max(line_proj) \\u003e= np.min(aabb_proj)):\n",
+ "lineno": 59,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 59,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 60,
+ "end_region_line": 62,
+ "line": " return False # No overlap on the line axis\n",
+ "lineno": 60,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 60,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 61,
+ "end_region_line": 62,
+ "line": "\n",
+ "lineno": 61,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 61,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 62,
+ "end_region_line": 62,
+ "line": " return True # No separating axis found, intersection exists\n",
+ "lineno": 62,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 62,
+ "start_region_line": 27
+ },
+ {
+ "end_outermost_loop": 63,
+ "end_region_line": 63,
+ "line": "\n",
+ "lineno": 63,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 63,
+ "start_region_line": 63
+ },
+ {
+ "end_outermost_loop": 64,
+ "end_region_line": 64,
+ "line": "\n",
+ "lineno": 64,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 64,
+ "start_region_line": 64
+ },
+ {
+ "end_outermost_loop": 88,
+ "end_region_line": 88,
+ "line": "def check_pts_in_AABB_cube(cube, pts):\n",
+ "lineno": 65,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 65,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 66,
+ "end_region_line": 88,
+ "line": " \"\"\"\n",
+ "lineno": 66,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 66,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 67,
+ "end_region_line": 88,
+ "line": " Check if any of the 'points lie inside the cube\n",
+ "lineno": 67,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 67,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 68,
+ "end_region_line": 88,
+ "line": " Parameters\n",
+ "lineno": 68,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 68,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 69,
+ "end_region_line": 88,
+ "line": " ----------\n",
+ "lineno": 69,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 69,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 70,
+ "end_region_line": 88,
+ "line": " cube: Array of points of cube (8x4)\n",
+ "lineno": 70,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 70,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 71,
+ "end_region_line": 88,
+ "line": " pts: Array of points to check\n",
+ "lineno": 71,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 71,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 72,
+ "end_region_line": 88,
+ "line": "\n",
+ "lineno": 72,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 72,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 73,
+ "end_region_line": 88,
+ "line": " Returns\n",
+ "lineno": 73,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 73,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 74,
+ "end_region_line": 88,
+ "line": " -------\n",
+ "lineno": 74,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 74,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 75,
+ "end_region_line": 88,
+ "line": " True/False\n",
+ "lineno": 75,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 75,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 76,
+ "end_region_line": 88,
+ "line": " \"\"\"\n",
+ "lineno": 76,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 76,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 77,
+ "end_region_line": 88,
+ "line": " xmax = max(cube[:, 0])\n",
+ "lineno": 77,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 77,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 78,
+ "end_region_line": 88,
+ "line": " xmin = min(cube[:, 0])\n",
+ "lineno": 78,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 78,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 79,
+ "end_region_line": 88,
+ "line": " ymax = max(cube[:, 1])\n",
+ "lineno": 79,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 79,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 80,
+ "end_region_line": 88,
+ "line": " ymin = min(cube[:, 1])\n",
+ "lineno": 80,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 80,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 81,
+ "end_region_line": 88,
+ "line": " zmax = max(cube[:, 2])\n",
+ "lineno": 81,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 81,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 82,
+ "end_region_line": 88,
+ "line": " zmin = min(cube[:, 2])\n",
+ "lineno": 82,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 82,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 83,
+ "end_region_line": 88,
+ "line": "\n",
+ "lineno": 83,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 83,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 87,
+ "end_region_line": 87,
+ "line": " for p in pts:\n",
+ "lineno": 84,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 84,
+ "start_region_line": 84
+ },
+ {
+ "end_outermost_loop": 87,
+ "end_region_line": 87,
+ "line": " inside = p[0] \\u003c= xmax and p[0] \\u003e= xmin and p[1] \\u003c= ymax and p[1] \\u003e= ymin and p[2] \\u003c= zmax and p[2] \\u003e= zmin\n",
+ "lineno": 85,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 84,
+ "start_region_line": 84
+ },
+ {
+ "end_outermost_loop": 87,
+ "end_region_line": 87,
+ "line": " if inside:\n",
+ "lineno": 86,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 84,
+ "start_region_line": 84
+ },
+ {
+ "end_outermost_loop": 87,
+ "end_region_line": 87,
+ "line": " return True\n",
+ "lineno": 87,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 84,
+ "start_region_line": 84
+ },
+ {
+ "end_outermost_loop": 88,
+ "end_region_line": 88,
+ "line": " return False\n",
+ "lineno": 88,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 88,
+ "start_region_line": 65
+ },
+ {
+ "end_outermost_loop": 89,
+ "end_region_line": 89,
+ "line": "\n",
+ "lineno": 89,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 89,
+ "start_region_line": 89
+ },
+ {
+ "end_outermost_loop": 112,
+ "end_region_line": 112,
+ "line": "def check_AABB_in_AABB_from_pts(pts1, pts2):\n",
+ "lineno": 90,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 90,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 91,
+ "end_region_line": 112,
+ "line": " \"\"\"\n",
+ "lineno": 91,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 91,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 92,
+ "end_region_line": 112,
+ "line": " Check if an AABB intersects another AABB from the given two sets of points\n",
+ "lineno": 92,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 92,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 93,
+ "end_region_line": 112,
+ "line": " \"\"\"\n",
+ "lineno": 93,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 93,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 94,
+ "end_region_line": 112,
+ "line": " xmax_1 = max(pts1[:, 0])\n",
+ "lineno": 94,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 94,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 95,
+ "end_region_line": 112,
+ "line": " xmin_1 = min(pts1[:, 0])\n",
+ "lineno": 95,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 95,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 96,
+ "end_region_line": 112,
+ "line": " ymax_1 = max(pts1[:, 1])\n",
+ "lineno": 96,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 96,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 97,
+ "end_region_line": 112,
+ "line": " ymin_1 = min(pts1[:, 1])\n",
+ "lineno": 97,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 97,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 98,
+ "end_region_line": 112,
+ "line": " zmax_1 = max(pts1[:, 2])\n",
+ "lineno": 98,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 98,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 99,
+ "end_region_line": 112,
+ "line": " zmin_1 = min(pts1[:, 2])\n",
+ "lineno": 99,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 99,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 100,
+ "end_region_line": 112,
+ "line": "\n",
+ "lineno": 100,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 100,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 101,
+ "end_region_line": 112,
+ "line": " xmax_2 = max(pts2[:, 0])\n",
+ "lineno": 101,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 101,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 102,
+ "end_region_line": 112,
+ "line": " xmin_2 = min(pts2[:, 0])\n",
+ "lineno": 102,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 102,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 103,
+ "end_region_line": 112,
+ "line": " ymax_2 = max(pts2[:, 1])\n",
+ "lineno": 103,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 103,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 104,
+ "end_region_line": 112,
+ "line": " ymin_2 = min(pts2[:, 1])\n",
+ "lineno": 104,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 104,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 105,
+ "end_region_line": 112,
+ "line": " zmax_2 = max(pts2[:, 2])\n",
+ "lineno": 105,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 105,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 106,
+ "end_region_line": 112,
+ "line": " zmin_2 = min(pts2[:, 2])\n",
+ "lineno": 106,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 106,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 107,
+ "end_region_line": 112,
+ "line": "\n",
+ "lineno": 107,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 107,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 108,
+ "end_region_line": 112,
+ "line": " cx = xmin_1\\u003c=xmax_2 and xmax_1\\u003e=xmin_2\n",
+ "lineno": 108,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 108,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 109,
+ "end_region_line": 112,
+ "line": " cy = ymin_1\\u003c=ymax_2 and ymax_1\\u003e=ymin_2\n",
+ "lineno": 109,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 109,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 110,
+ "end_region_line": 112,
+ "line": " cz = zmin_1\\u003c=zmax_2 and zmax_1\\u003e=zmin_2\n",
+ "lineno": 110,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 110,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 111,
+ "end_region_line": 112,
+ "line": " \n",
+ "lineno": 111,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 111,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 112,
+ "end_region_line": 112,
+ "line": " return cx and cy and cz\n",
+ "lineno": 112,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 112,
+ "start_region_line": 90
+ },
+ {
+ "end_outermost_loop": 113,
+ "end_region_line": 113,
+ "line": "\n",
+ "lineno": 113,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 113,
+ "start_region_line": 113
+ },
+ {
+ "end_outermost_loop": 114,
+ "end_region_line": 114,
+ "line": "\n",
+ "lineno": 114,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 114,
+ "start_region_line": 114
+ },
+ {
+ "end_outermost_loop": 135,
+ "end_region_line": 135,
+ "line": "def check_mesh_triangle_edges_in_cube(mesh_triangles,cube):\n",
+ "lineno": 115,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 115,
+ "start_region_line": 115
+ },
+ {
+ "end_outermost_loop": 135,
+ "end_region_line": 135,
+ "line": " # Check a set of mesh's triangles intersect an AABB cube\n",
+ "lineno": 116,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 115,
+ "start_region_line": 115
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": " while len(mesh_triangles):\n",
+ "lineno": 117,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": " # choose a random triangle indices\n",
+ "lineno": 118,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": " random_index = random.randint(0, len(mesh_triangles) - 1)\n",
+ "lineno": 119,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": " points = mesh_triangles[random_index]\n",
+ "lineno": 120,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": " mesh_triangles.pop(random_index)\n",
+ "lineno": 121,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": "\n",
+ "lineno": 122,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": " # Three triangle sides\n",
+ "lineno": 123,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": " set_1 = [points[0],points[1]]\n",
+ "lineno": 124,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": " set_2 = [points[0],points[2]]\n",
+ "lineno": 125,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": " set_3 = [points[1],points[2]]\n",
+ "lineno": 126,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": "\n",
+ "lineno": 127,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": " # Sample three equilinear points on each side and test for AABB intersection\n",
+ "lineno": 128,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 117
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": " for set in [set_1,set_2,set_3]:\n",
+ "lineno": 129,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 129
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": " mid = np.add(set[0], set[1])/2\n",
+ "lineno": 130,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 129
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": " mid1 = np.add(mid, set[0])/2\n",
+ "lineno": 131,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 129
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": " mid2 = np.add(mid, set[1])/2\n",
+ "lineno": 132,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 129
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": " if check_pts_in_AABB_cube(cube,[mid, mid1, mid2]):\n",
+ "lineno": 133,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 129
+ },
+ {
+ "end_outermost_loop": 134,
+ "end_region_line": 134,
+ "line": " return True\n",
+ "lineno": 134,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 117,
+ "start_region_line": 129
+ },
+ {
+ "end_outermost_loop": 135,
+ "end_region_line": 135,
+ "line": " return False\n",
+ "lineno": 135,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 135,
+ "start_region_line": 115
+ },
+ {
+ "end_outermost_loop": 136,
+ "end_region_line": 136,
+ "line": "\n",
+ "lineno": 136,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 136,
+ "start_region_line": 136
+ },
+ {
+ "end_outermost_loop": 137,
+ "end_region_line": 137,
+ "line": "# def check_mesh_triangle_edges_in_cube(mesh_triangles,cube):\n",
+ "lineno": 137,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 137,
+ "start_region_line": 137
+ },
+ {
+ "end_outermost_loop": 138,
+ "end_region_line": 138,
+ "line": "# for points in mesh_triangles:\n",
+ "lineno": 138,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 138,
+ "start_region_line": 138
+ },
+ {
+ "end_outermost_loop": 139,
+ "end_region_line": 139,
+ "line": "# set_1 = [points[0],points[1]]\n",
+ "lineno": 139,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 139,
+ "start_region_line": 139
+ },
+ {
+ "end_outermost_loop": 140,
+ "end_region_line": 140,
+ "line": "# set_2 = [points[0],points[2]]\n",
+ "lineno": 140,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 140,
+ "start_region_line": 140
+ },
+ {
+ "end_outermost_loop": 141,
+ "end_region_line": 141,
+ "line": "# set_3 = [points[1],points[2]]\n",
+ "lineno": 141,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 141,
+ "start_region_line": 141
+ },
+ {
+ "end_outermost_loop": 142,
+ "end_region_line": 142,
+ "line": "# for set in [set_1,set_2,set_3]:\n",
+ "lineno": 142,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 142,
+ "start_region_line": 142
+ },
+ {
+ "end_outermost_loop": 143,
+ "end_region_line": 143,
+ "line": "# mid = np.add(set[0],set[1])/2\n",
+ "lineno": 143,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 143,
+ "start_region_line": 143
+ },
+ {
+ "end_outermost_loop": 144,
+ "end_region_line": 144,
+ "line": "# if check_pts_in_AABB_cube(cube,[mid]):\n",
+ "lineno": 144,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 144,
+ "start_region_line": 144
+ },
+ {
+ "end_outermost_loop": 145,
+ "end_region_line": 145,
+ "line": "# return True\n",
+ "lineno": 145,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 145,
+ "start_region_line": 145
+ },
+ {
+ "end_outermost_loop": 146,
+ "end_region_line": 146,
+ "line": "# mid1 = np.add(mid, set[0])/2\n",
+ "lineno": 146,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 146,
+ "start_region_line": 146
+ },
+ {
+ "end_outermost_loop": 147,
+ "end_region_line": 147,
+ "line": "# if check_pts_in_AABB_cube(cube,[mid1]):\n",
+ "lineno": 147,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 147,
+ "start_region_line": 147
+ },
+ {
+ "end_outermost_loop": 148,
+ "end_region_line": 148,
+ "line": "# return True\n",
+ "lineno": 148,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 148,
+ "start_region_line": 148
+ },
+ {
+ "end_outermost_loop": 149,
+ "end_region_line": 149,
+ "line": "# mid2 = np.add(mid, set[1])/2\n",
+ "lineno": 149,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 149,
+ "start_region_line": 149
+ },
+ {
+ "end_outermost_loop": 150,
+ "end_region_line": 150,
+ "line": "# if check_pts_in_AABB_cube(cube,[mid2]):\n",
+ "lineno": 150,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 150,
+ "start_region_line": 150
+ },
+ {
+ "end_outermost_loop": 151,
+ "end_region_line": 151,
+ "line": "# return True\n",
+ "lineno": 151,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 151,
+ "start_region_line": 151
+ },
+ {
+ "end_outermost_loop": 152,
+ "end_region_line": 152,
+ "line": "# return False\n",
+ "lineno": 152,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 152,
+ "start_region_line": 152
+ },
+ {
+ "end_outermost_loop": 153,
+ "end_region_line": 153,
+ "line": "\n",
+ "lineno": 153,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 153,
+ "start_region_line": 153
+ },
+ {
+ "end_outermost_loop": 154,
+ "end_region_line": 154,
+ "line": "\n",
+ "lineno": 154,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 154,
+ "start_region_line": 154
+ },
+ {
+ "end_outermost_loop": 172,
+ "end_region_line": 172,
+ "line": "def check_ppd_edges_in_cube(cube,cube_edge,edge_indices):\n",
+ "lineno": 155,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 155,
+ "start_region_line": 155
+ },
+ {
+ "end_outermost_loop": 158,
+ "end_region_line": 172,
+ "line": " if len(edge_indices)!=12:\n",
+ "lineno": 156,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 156,
+ "start_region_line": 155
+ },
+ {
+ "end_outermost_loop": 157,
+ "end_region_line": 172,
+ "line": " print('Invalid PPD provided to check_ppd_edges_in_cube')\n",
+ "lineno": 157,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 157,
+ "start_region_line": 155
+ },
+ {
+ "end_outermost_loop": 158,
+ "end_region_line": 172,
+ "line": " return False\n",
+ "lineno": 158,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 158,
+ "start_region_line": 155
+ },
+ {
+ "end_outermost_loop": 159,
+ "end_region_line": 172,
+ "line": " aabb_min=np.array([min(cube[:, 0]),min(cube[:, 1]),min(cube[:, 2])],dtype=np.float32)\n",
+ "lineno": 159,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 159,
+ "start_region_line": 155
+ },
+ {
+ "end_outermost_loop": 160,
+ "end_region_line": 172,
+ "line": " aabb_max = np.array([max(cube[:, 0]),max(cube[:, 1]),max(cube[:, 2])],dtype=np.float32)\n",
+ "lineno": 160,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 160,
+ "start_region_line": 155
+ },
+ {
+ "end_outermost_loop": 161,
+ "end_region_line": 172,
+ "line": " print('EE',cube_edge)\n",
+ "lineno": 161,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 161,
+ "start_region_line": 155
+ },
+ {
+ "end_outermost_loop": 171,
+ "end_region_line": 171,
+ "line": " for ei in edge_indices:\n",
+ "lineno": 162,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 162,
+ "start_region_line": 162
+ },
+ {
+ "end_outermost_loop": 171,
+ "end_region_line": 171,
+ "line": " e0=cube_edge[ei][0][0:3]\n",
+ "lineno": 163,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 162,
+ "start_region_line": 162
+ },
+ {
+ "end_outermost_loop": 171,
+ "end_region_line": 171,
+ "line": " e1=cube_edge[ei][1][0:3]\n",
+ "lineno": 164,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 162,
+ "start_region_line": 162
+ },
+ {
+ "end_outermost_loop": 171,
+ "end_region_line": 171,
+ "line": " print('----',ei)\n",
+ "lineno": 165,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 162,
+ "start_region_line": 162
+ },
+ {
+ "end_outermost_loop": 171,
+ "end_region_line": 171,
+ "line": " print('e0',e0)\n",
+ "lineno": 166,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 162,
+ "start_region_line": 162
+ },
+ {
+ "end_outermost_loop": 171,
+ "end_region_line": 171,
+ "line": " print('e1', e1)\n",
+ "lineno": 167,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 162,
+ "start_region_line": 162
+ },
+ {
+ "end_outermost_loop": 171,
+ "end_region_line": 171,
+ "line": " print('aabb_min', aabb_min)\n",
+ "lineno": 168,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 162,
+ "start_region_line": 162
+ },
+ {
+ "end_outermost_loop": 171,
+ "end_region_line": 171,
+ "line": " print('aabb_max', aabb_max)\n",
+ "lineno": 169,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 162,
+ "start_region_line": 162
+ },
+ {
+ "end_outermost_loop": 171,
+ "end_region_line": 171,
+ "line": " if line_box_sat_intersection(e0,e1, aabb_min, aabb_max):\n",
+ "lineno": 170,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 162,
+ "start_region_line": 162
+ },
+ {
+ "end_outermost_loop": 171,
+ "end_region_line": 171,
+ "line": " return True\n",
+ "lineno": 171,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 162,
+ "start_region_line": 162
+ },
+ {
+ "end_outermost_loop": 172,
+ "end_region_line": 172,
+ "line": " return False\n",
+ "lineno": 172,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 172,
+ "start_region_line": 155
+ },
+ {
+ "end_outermost_loop": 173,
+ "end_region_line": 173,
+ "line": "\n",
+ "lineno": 173,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 173,
+ "start_region_line": 173
+ },
+ {
+ "end_outermost_loop": 188,
+ "end_region_line": 188,
+ "line": "def closest_pair_3d(points1, points2):\n",
+ "lineno": 174,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 174,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 175,
+ "end_region_line": 188,
+ "line": " \"\"\"\n",
+ "lineno": 175,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 175,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 176,
+ "end_region_line": 188,
+ "line": " Find the closest pair of 3D points from two lists of 3D points.\n",
+ "lineno": 176,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 176,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 177,
+ "end_region_line": 188,
+ "line": " \"\"\"\n",
+ "lineno": 177,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 177,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 178,
+ "end_region_line": 188,
+ "line": " closest_distance = float('inf')\n",
+ "lineno": 178,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 178,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 179,
+ "end_region_line": 188,
+ "line": " closest_pair = None\n",
+ "lineno": 179,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 179,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 180,
+ "end_region_line": 188,
+ "line": " \n",
+ "lineno": 180,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 180,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 186,
+ "end_region_line": 186,
+ "line": " for p1 in points1:\n",
+ "lineno": 181,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 181,
+ "start_region_line": 181
+ },
+ {
+ "end_outermost_loop": 186,
+ "end_region_line": 186,
+ "line": " for p2 in points2:\n",
+ "lineno": 182,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 181,
+ "start_region_line": 182
+ },
+ {
+ "end_outermost_loop": 186,
+ "end_region_line": 186,
+ "line": " dist = np.linalg.norm(p1-p2)\n",
+ "lineno": 183,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 181,
+ "start_region_line": 182
+ },
+ {
+ "end_outermost_loop": 186,
+ "end_region_line": 186,
+ "line": " if dist \\u003c closest_distance:\n",
+ "lineno": 184,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 181,
+ "start_region_line": 182
+ },
+ {
+ "end_outermost_loop": 186,
+ "end_region_line": 186,
+ "line": " closest_distance = dist\n",
+ "lineno": 185,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 181,
+ "start_region_line": 182
+ },
+ {
+ "end_outermost_loop": 186,
+ "end_region_line": 186,
+ "line": " closest_pair = (p1, p2)\n",
+ "lineno": 186,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 181,
+ "start_region_line": 182
+ },
+ {
+ "end_outermost_loop": 187,
+ "end_region_line": 188,
+ "line": " \n",
+ "lineno": 187,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 187,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 188,
+ "end_region_line": 188,
+ "line": " return closest_pair, closest_distance\n",
+ "lineno": 188,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 188,
+ "start_region_line": 174
+ },
+ {
+ "end_outermost_loop": 189,
+ "end_region_line": 189,
+ "line": " \n",
+ "lineno": 189,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 189,
+ "start_region_line": 189
+ },
+ {
+ "end_outermost_loop": 190,
+ "end_region_line": 190,
+ "line": "# #######################################################################\n",
+ "lineno": 190,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 190,
+ "start_region_line": 190
+ },
+ {
+ "end_outermost_loop": 191,
+ "end_region_line": 191,
+ "line": "\n",
+ "lineno": 191,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 191,
+ "start_region_line": 191
+ },
+ {
+ "end_outermost_loop": 295,
+ "end_region_line": 295,
+ "line": "class CollisionLink:\n",
+ "lineno": 192,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 192,
+ "start_region_line": 192
+ },
+ {
+ "end_outermost_loop": 208,
+ "end_region_line": 208,
+ "line": " def __init__(self,link_name,urdf,mesh_path,max_mesh_points):\n",
+ "lineno": 193,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 193,
+ "start_region_line": 193
+ },
+ {
+ "end_outermost_loop": 194,
+ "end_region_line": 208,
+ "line": " self.name=link_name\n",
+ "lineno": 194,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 194,
+ "start_region_line": 193
+ },
+ {
+ "end_outermost_loop": 195,
+ "end_region_line": 208,
+ "line": " self.link = urdf.link_map[link_name]\n",
+ "lineno": 195,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 195,
+ "start_region_line": 193
+ },
+ {
+ "end_outermost_loop": 196,
+ "end_region_line": 208,
+ "line": " stl_filename = str(mesh_path) + self.link.collisions[0].geometry.mesh.filename[1:]\n",
+ "lineno": 196,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 196,
+ "start_region_line": 193
+ },
+ {
+ "end_outermost_loop": 197,
+ "end_region_line": 208,
+ "line": " self.mesh = meshio.read(stl_filename)\n",
+ "lineno": 197,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 197,
+ "start_region_line": 193
+ },
+ {
+ "end_outermost_loop": 198,
+ "end_region_line": 208,
+ "line": " pts = self.mesh.points\n",
+ "lineno": 198,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 198,
+ "start_region_line": 193
+ },
+ {
+ "end_outermost_loop": 199,
+ "end_region_line": 208,
+ "line": " self.points = np.hstack((pts, np.ones([pts.shape[0], 1], dtype=np.float32))) # One extend to Nx4 array\n",
+ "lineno": 199,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 199,
+ "start_region_line": 193
+ },
+ {
+ "end_outermost_loop": 200,
+ "end_region_line": 208,
+ "line": " self.in_collision= False\n",
+ "lineno": 200,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 200,
+ "start_region_line": 193
+ },
+ {
+ "end_outermost_loop": 201,
+ "end_region_line": 208,
+ "line": " self.was_in_collision = False\n",
+ "lineno": 201,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 201,
+ "start_region_line": 193
+ },
+ {
+ "end_outermost_loop": 202,
+ "end_region_line": 208,
+ "line": " self.is_aabb=self.check_AABB(self.points)\n",
+ "lineno": 202,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 202,
+ "start_region_line": 193
+ },
+ {
+ "end_outermost_loop": 203,
+ "end_region_line": 208,
+ "line": " self.is_valid=True\n",
+ "lineno": 203,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 203,
+ "start_region_line": 193
+ },
+ {
+ "end_outermost_loop": 207,
+ "end_region_line": 208,
+ "line": " if pts.shape[0] \\u003e max_mesh_points:\n",
+ "lineno": 204,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 204,
+ "start_region_line": 193
+ },
+ {
+ "end_outermost_loop": 205,
+ "end_region_line": 208,
+ "line": " print('Incorrect size of points for link:', link_name, pts.shape)\n",
+ "lineno": 205,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 205,
+ "start_region_line": 193
+ },
+ {
+ "end_outermost_loop": 206,
+ "end_region_line": 208,
+ "line": " print('Ignoring collision link %s' % link_name)\n",
+ "lineno": 206,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 206,
+ "start_region_line": 193
+ },
+ {
+ "end_outermost_loop": 207,
+ "end_region_line": 208,
+ "line": " self.is_valid=False\n",
+ "lineno": 207,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 207,
+ "start_region_line": 193
+ },
+ {
+ "end_outermost_loop": 208,
+ "end_region_line": 208,
+ "line": " self.pose=None\n",
+ "lineno": 208,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 208,
+ "start_region_line": 193
+ },
+ {
+ "end_outermost_loop": 295,
+ "end_region_line": 295,
+ "line": " #self.edge_indices_ppd=self.find_edge_indices_PPD()\n",
+ "lineno": 209,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 192,
+ "start_region_line": 192
+ },
+ {
+ "end_outermost_loop": 210,
+ "end_region_line": 295,
+ "line": "\n",
+ "lineno": 210,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 210,
+ "start_region_line": 192
+ },
+ {
+ "end_outermost_loop": 211,
+ "end_region_line": 295,
+ "line": "\n",
+ "lineno": 211,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 211,
+ "start_region_line": 192
+ },
+ {
+ "end_outermost_loop": 213,
+ "end_region_line": 213,
+ "line": " def is_ppd(self):\n",
+ "lineno": 212,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 212,
+ "start_region_line": 212
+ },
+ {
+ "end_outermost_loop": 213,
+ "end_region_line": 213,
+ "line": " return self.points.shape[0]==8\n",
+ "lineno": 213,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 213,
+ "start_region_line": 212
+ },
+ {
+ "end_outermost_loop": 214,
+ "end_region_line": 295,
+ "line": "\n",
+ "lineno": 214,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 214,
+ "start_region_line": 192
+ },
+ {
+ "end_outermost_loop": 216,
+ "end_region_line": 216,
+ "line": " def set_pose(self,p):\n",
+ "lineno": 215,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 215,
+ "start_region_line": 215
+ },
+ {
+ "end_outermost_loop": 216,
+ "end_region_line": 216,
+ "line": " self.pose=p\n",
+ "lineno": 216,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 216,
+ "start_region_line": 215
+ },
+ {
+ "end_outermost_loop": 217,
+ "end_region_line": 295,
+ "line": "\n",
+ "lineno": 217,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 217,
+ "start_region_line": 192
+ },
+ {
+ "end_outermost_loop": 224,
+ "end_region_line": 224,
+ "line": " def pretty_print(self):\n",
+ "lineno": 218,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 218,
+ "start_region_line": 218
+ },
+ {
+ "end_outermost_loop": 219,
+ "end_region_line": 224,
+ "line": " print('-- CollisionLink %s --'%self.name)\n",
+ "lineno": 219,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 219,
+ "start_region_line": 218
+ },
+ {
+ "end_outermost_loop": 220,
+ "end_region_line": 224,
+ "line": " print('AABB Cube',self.is_aabb)\n",
+ "lineno": 220,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 220,
+ "start_region_line": 218
+ },
+ {
+ "end_outermost_loop": 221,
+ "end_region_line": 224,
+ "line": " print('Is Valid', self.is_valid)\n",
+ "lineno": 221,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 221,
+ "start_region_line": 218
+ },
+ {
+ "end_outermost_loop": 222,
+ "end_region_line": 224,
+ "line": " print('In collision',self.in_collision)\n",
+ "lineno": 222,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 222,
+ "start_region_line": 218
+ },
+ {
+ "end_outermost_loop": 223,
+ "end_region_line": 224,
+ "line": " print('Was in collision',self.was_in_collision)\n",
+ "lineno": 223,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 223,
+ "start_region_line": 218
+ },
+ {
+ "end_outermost_loop": 224,
+ "end_region_line": 224,
+ "line": " print('Mesh size',self.points.shape)\n",
+ "lineno": 224,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 224,
+ "start_region_line": 218
+ },
+ {
+ "end_outermost_loop": 225,
+ "end_region_line": 295,
+ "line": "\n",
+ "lineno": 225,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 225,
+ "start_region_line": 192
+ },
+ {
+ "end_outermost_loop": 260,
+ "end_region_line": 260,
+ "line": " def find_edge_indices_PPD(self):\n",
+ "lineno": 226,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 226,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 227,
+ "end_region_line": 260,
+ "line": " \"\"\"\n",
+ "lineno": 227,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 227,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 228,
+ "end_region_line": 260,
+ "line": " Return the indices for each edge assuming the link is a parallelpiped (PPD)\n",
+ "lineno": 228,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 228,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 229,
+ "end_region_line": 260,
+ "line": " \"\"\"\n",
+ "lineno": 229,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 229,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 230,
+ "end_region_line": 260,
+ "line": "\n",
+ "lineno": 230,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 230,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 231,
+ "end_region_line": 260,
+ "line": " triangles=self.mesh.cells_dict['triangle']\n",
+ "lineno": 231,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 231,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 232,
+ "end_region_line": 260,
+ "line": "\n",
+ "lineno": 232,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 232,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 238,
+ "end_region_line": 238,
+ "line": " for t in triangles:\n",
+ "lineno": 233,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 233,
+ "start_region_line": 233
+ },
+ {
+ "end_outermost_loop": 238,
+ "end_region_line": 238,
+ "line": " idx_pairs=[[0,1],[0,2],[1,2]]\n",
+ "lineno": 234,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 233,
+ "start_region_line": 233
+ },
+ {
+ "end_outermost_loop": 238,
+ "end_region_line": 238,
+ "line": " edge_lens=[]\n",
+ "lineno": 235,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 233,
+ "start_region_line": 233
+ },
+ {
+ "end_outermost_loop": 238,
+ "end_region_line": 237,
+ "line": " for ii in idx_pairs:\n",
+ "lineno": 236,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 233,
+ "start_region_line": 236
+ },
+ {
+ "end_outermost_loop": 238,
+ "end_region_line": 237,
+ "line": " edge_lens.append(np.linalg.norm(self.points[ii[0]]-self.points[ii[2]]))\n",
+ "lineno": 237,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 233,
+ "start_region_line": 236
+ },
+ {
+ "end_outermost_loop": 238,
+ "end_region_line": 238,
+ "line": " exterior_edges = np.array(idx_pairs)[np.argsort(np.array(edge_lens))][0:2] #indices of two shortest legs of triangle\n",
+ "lineno": 238,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 233,
+ "start_region_line": 233
+ },
+ {
+ "end_outermost_loop": 239,
+ "end_region_line": 260,
+ "line": "\n",
+ "lineno": 239,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 239,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 240,
+ "end_region_line": 260,
+ "line": "\n",
+ "lineno": 240,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 240,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 241,
+ "end_region_line": 260,
+ "line": "\n",
+ "lineno": 241,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 241,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 242,
+ "end_region_line": 260,
+ "line": "\n",
+ "lineno": 242,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 242,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 243,
+ "end_region_line": 260,
+ "line": " px=self.points.shape[0]\n",
+ "lineno": 243,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 243,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 260,
+ "end_region_line": 260,
+ "line": " # if not self.is_ppd():\n",
+ "lineno": 244,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 226,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 260,
+ "end_region_line": 260,
+ "line": " # return np.array([])\n",
+ "lineno": 245,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 226,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 246,
+ "end_region_line": 260,
+ "line": " idx=[]\n",
+ "lineno": 246,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 246,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 247,
+ "end_region_line": 260,
+ "line": " lens=[]\n",
+ "lineno": 247,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 247,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 260,
+ "end_region_line": 260,
+ "line": " #Toss out really short edge as is a mesh file artifact\n",
+ "lineno": 248,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 226,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 249,
+ "end_region_line": 260,
+ "line": "\n",
+ "lineno": 249,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 249,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 255,
+ "end_region_line": 255,
+ "line": " for i in range(px):\n",
+ "lineno": 250,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 250,
+ "start_region_line": 250
+ },
+ {
+ "end_outermost_loop": 255,
+ "end_region_line": 255,
+ "line": " for j in range(i+1,px):\n",
+ "lineno": 251,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 250,
+ "start_region_line": 251
+ },
+ {
+ "end_outermost_loop": 255,
+ "end_region_line": 255,
+ "line": " ll = np.linalg.norm(self.points[i] - self.points[j])\n",
+ "lineno": 252,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 250,
+ "start_region_line": 251
+ },
+ {
+ "end_outermost_loop": 255,
+ "end_region_line": 255,
+ "line": " if ll\\u003eeps:\n",
+ "lineno": 253,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 250,
+ "start_region_line": 251
+ },
+ {
+ "end_outermost_loop": 255,
+ "end_region_line": 255,
+ "line": " idx.append([i,j])\n",
+ "lineno": 254,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 250,
+ "start_region_line": 251
+ },
+ {
+ "end_outermost_loop": 255,
+ "end_region_line": 255,
+ "line": " lens.append(ll)\n",
+ "lineno": 255,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 250,
+ "start_region_line": 251
+ },
+ {
+ "end_outermost_loop": 260,
+ "end_region_line": 260,
+ "line": " #return 12 shortest lengths of all possible combinations\n",
+ "lineno": 256,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 226,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 257,
+ "end_region_line": 260,
+ "line": " q= np.array(idx)[np.argsort(np.array(lens))][0:12]\n",
+ "lineno": 257,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 257,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 258,
+ "end_region_line": 260,
+ "line": " lens.sort()\n",
+ "lineno": 258,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 258,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 259,
+ "end_region_line": 260,
+ "line": " print('LENS',lens)\n",
+ "lineno": 259,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 259,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 260,
+ "end_region_line": 260,
+ "line": " return q\n",
+ "lineno": 260,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 260,
+ "start_region_line": 226
+ },
+ {
+ "end_outermost_loop": 261,
+ "end_region_line": 295,
+ "line": " \n",
+ "lineno": 261,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 261,
+ "start_region_line": 192
+ },
+ {
+ "end_outermost_loop": 270,
+ "end_region_line": 270,
+ "line": " def get_triangles(self):\n",
+ "lineno": 262,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 262,
+ "start_region_line": 262
+ },
+ {
+ "end_outermost_loop": 263,
+ "end_region_line": 270,
+ "line": " triangles_idx=self.mesh.cells_dict['triangle']\n",
+ "lineno": 263,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 263,
+ "start_region_line": 262
+ },
+ {
+ "end_outermost_loop": 264,
+ "end_region_line": 270,
+ "line": " triangles = []\n",
+ "lineno": 264,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 264,
+ "start_region_line": 262
+ },
+ {
+ "end_outermost_loop": 269,
+ "end_region_line": 269,
+ "line": " for t_set in triangles_idx:\n",
+ "lineno": 265,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 265,
+ "start_region_line": 265
+ },
+ {
+ "end_outermost_loop": 269,
+ "end_region_line": 269,
+ "line": " p1 = self.pose[t_set[0]]\n",
+ "lineno": 266,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 265,
+ "start_region_line": 265
+ },
+ {
+ "end_outermost_loop": 269,
+ "end_region_line": 269,
+ "line": " p2 = self.pose[t_set[1]]\n",
+ "lineno": 267,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 265,
+ "start_region_line": 265
+ },
+ {
+ "end_outermost_loop": 269,
+ "end_region_line": 269,
+ "line": " p3 = self.pose[t_set[2]]\n",
+ "lineno": 268,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 265,
+ "start_region_line": 265
+ },
+ {
+ "end_outermost_loop": 269,
+ "end_region_line": 269,
+ "line": " triangles.append([p1,p2,p3])\n",
+ "lineno": 269,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 265,
+ "start_region_line": 265
+ },
+ {
+ "end_outermost_loop": 270,
+ "end_region_line": 270,
+ "line": " return triangles\n",
+ "lineno": 270,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 270,
+ "start_region_line": 262
+ },
+ {
+ "end_outermost_loop": 271,
+ "end_region_line": 295,
+ "line": "\n",
+ "lineno": 271,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 271,
+ "start_region_line": 192
+ },
+ {
+ "end_outermost_loop": 295,
+ "end_region_line": 295,
+ "line": " def check_AABB(self,pts):\n",
+ "lineno": 272,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 272,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 273,
+ "end_region_line": 295,
+ "line": " \"\"\"\n",
+ "lineno": 273,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 273,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 274,
+ "end_region_line": 295,
+ "line": " Check if points are axis aligned (roughly) and form a rectangular parallelpiped (eg AABB)\n",
+ "lineno": 274,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 274,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 275,
+ "end_region_line": 295,
+ "line": "\n",
+ "lineno": 275,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 275,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 276,
+ "end_region_line": 295,
+ "line": " Parameters\n",
+ "lineno": 276,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 276,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 277,
+ "end_region_line": 295,
+ "line": " ----------\n",
+ "lineno": 277,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 277,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 278,
+ "end_region_line": 295,
+ "line": " pts of mesh (8x4)\n",
+ "lineno": 278,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 278,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 279,
+ "end_region_line": 295,
+ "line": "\n",
+ "lineno": 279,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 279,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 280,
+ "end_region_line": 295,
+ "line": " Returns\n",
+ "lineno": 280,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 280,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 281,
+ "end_region_line": 295,
+ "line": " -------\n",
+ "lineno": 281,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 281,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 282,
+ "end_region_line": 295,
+ "line": " True / False\n",
+ "lineno": 282,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 282,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 283,
+ "end_region_line": 295,
+ "line": " \"\"\"\n",
+ "lineno": 283,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 283,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 295,
+ "end_region_line": 295,
+ "line": " # Check that each x,y,z of each point has two nearly (eps) idential values\n",
+ "lineno": 284,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 272,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 285,
+ "end_region_line": 295,
+ "line": " x = pts[:, 0]\n",
+ "lineno": 285,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 285,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 286,
+ "end_region_line": 295,
+ "line": " y = pts[:, 1]\n",
+ "lineno": 286,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 286,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 287,
+ "end_region_line": 295,
+ "line": " z = pts[:, 2]\n",
+ "lineno": 287,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 287,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 288,
+ "end_region_line": 295,
+ "line": " eps = .001 # meters\n",
+ "lineno": 288,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 288,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 294,
+ "end_region_line": 294,
+ "line": " for ridx in range(8):\n",
+ "lineno": 289,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 289,
+ "start_region_line": 289
+ },
+ {
+ "end_outermost_loop": 294,
+ "end_region_line": 294,
+ "line": " sx = sum(abs((x - x[ridx])) \\u003c eps)\n",
+ "lineno": 290,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 289,
+ "start_region_line": 289
+ },
+ {
+ "end_outermost_loop": 294,
+ "end_region_line": 294,
+ "line": " sy = sum(abs((y - y[ridx])) \\u003c eps)\n",
+ "lineno": 291,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 289,
+ "start_region_line": 289
+ },
+ {
+ "end_outermost_loop": 294,
+ "end_region_line": 294,
+ "line": " sz = sum(abs((y - y[ridx])) \\u003c eps)\n",
+ "lineno": 292,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 289,
+ "start_region_line": 289
+ },
+ {
+ "end_outermost_loop": 294,
+ "end_region_line": 294,
+ "line": " if sx + sy + sz != 12:\n",
+ "lineno": 293,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 289,
+ "start_region_line": 289
+ },
+ {
+ "end_outermost_loop": 294,
+ "end_region_line": 294,
+ "line": " return False\n",
+ "lineno": 294,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 289,
+ "start_region_line": 289
+ },
+ {
+ "end_outermost_loop": 295,
+ "end_region_line": 295,
+ "line": " return True\n",
+ "lineno": 295,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 295,
+ "start_region_line": 272
+ },
+ {
+ "end_outermost_loop": 296,
+ "end_region_line": 296,
+ "line": "\n",
+ "lineno": 296,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 296,
+ "start_region_line": 296
+ },
+ {
+ "end_outermost_loop": 313,
+ "end_region_line": 313,
+ "line": "class CollisionPair:\n",
+ "lineno": 297,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 297,
+ "start_region_line": 297
+ },
+ {
+ "end_outermost_loop": 307,
+ "end_region_line": 307,
+ "line": " def __init__(self, name,link_pts,link_cube,detect_as):\n",
+ "lineno": 298,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 298,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 299,
+ "end_region_line": 307,
+ "line": " self.in_collision=False\n",
+ "lineno": 299,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 299,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 300,
+ "end_region_line": 307,
+ "line": " self.was_in_collision=False\n",
+ "lineno": 300,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 300,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 301,
+ "end_region_line": 307,
+ "line": " self.link_cube=link_cube\n",
+ "lineno": 301,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 301,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 302,
+ "end_region_line": 307,
+ "line": " self.link_pts=link_pts\n",
+ "lineno": 302,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 302,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 303,
+ "end_region_line": 307,
+ "line": " self.detect_as=detect_as\n",
+ "lineno": 303,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 303,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 304,
+ "end_region_line": 307,
+ "line": " self.name=name\n",
+ "lineno": 304,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 304,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 305,
+ "end_region_line": 307,
+ "line": " self.is_valid=self.link_cube.is_valid and self.link_pts.is_valid and self.link_cube.is_aabb\n",
+ "lineno": 305,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 305,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 307,
+ "end_region_line": 307,
+ "line": " if not self.is_valid:\n",
+ "lineno": 306,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 306,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 307,
+ "end_region_line": 307,
+ "line": " print('Dropping monitor of collision pair %s'%self.name_id)\n",
+ "lineno": 307,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 307,
+ "start_region_line": 298
+ },
+ {
+ "end_outermost_loop": 308,
+ "end_region_line": 313,
+ "line": "\n",
+ "lineno": 308,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 308,
+ "start_region_line": 297
+ },
+ {
+ "end_outermost_loop": 313,
+ "end_region_line": 313,
+ "line": " def pretty_print(self):\n",
+ "lineno": 309,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 309,
+ "start_region_line": 309
+ },
+ {
+ "end_outermost_loop": 310,
+ "end_region_line": 313,
+ "line": " print('-------- Collision Pair %s ----------------'%self.name_id.upper())\n",
+ "lineno": 310,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 310,
+ "start_region_line": 309
+ },
+ {
+ "end_outermost_loop": 311,
+ "end_region_line": 313,
+ "line": " print('In collision',self.in_collision)\n",
+ "lineno": 311,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 311,
+ "start_region_line": 309
+ },
+ {
+ "end_outermost_loop": 312,
+ "end_region_line": 313,
+ "line": " print('Was in collision',self.was_in_collision)\n",
+ "lineno": 312,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 312,
+ "start_region_line": 309
+ },
+ {
+ "end_outermost_loop": 313,
+ "end_region_line": 313,
+ "line": " print('Is Valid',self.is_valid)\n",
+ "lineno": 313,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 313,
+ "start_region_line": 309
+ },
+ {
+ "end_outermost_loop": 314,
+ "end_region_line": 314,
+ "line": " # print('--Link Cube--')\n",
+ "lineno": 314,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 314,
+ "start_region_line": 314
+ },
+ {
+ "end_outermost_loop": 315,
+ "end_region_line": 315,
+ "line": " # self.link_cube.pretty_print()\n",
+ "lineno": 315,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 315,
+ "start_region_line": 315
+ },
+ {
+ "end_outermost_loop": 316,
+ "end_region_line": 316,
+ "line": " # print('--Link Pts--')\n",
+ "lineno": 316,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 316,
+ "start_region_line": 316
+ },
+ {
+ "end_outermost_loop": 317,
+ "end_region_line": 317,
+ "line": " # self.link_pts.pretty_print()\n",
+ "lineno": 317,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 317,
+ "start_region_line": 317
+ },
+ {
+ "end_outermost_loop": 318,
+ "end_region_line": 318,
+ "line": "\n",
+ "lineno": 318,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 318,
+ "start_region_line": 318
+ },
+ {
+ "end_outermost_loop": 319,
+ "end_region_line": 319,
+ "line": "\n",
+ "lineno": 319,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 319,
+ "start_region_line": 319
+ },
+ {
+ "end_outermost_loop": 352,
+ "end_region_line": 352,
+ "line": "class CollisionJoint:\n",
+ "lineno": 320,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 320,
+ "start_region_line": 320
+ },
+ {
+ "end_outermost_loop": 327,
+ "end_region_line": 327,
+ "line": " def __init__(self, joint_name):\n",
+ "lineno": 321,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 321,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 322,
+ "end_region_line": 327,
+ "line": " self.name=joint_name\n",
+ "lineno": 322,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 322,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 323,
+ "end_region_line": 327,
+ "line": " self.active_collisions=[]\n",
+ "lineno": 323,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 323,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 324,
+ "end_region_line": 327,
+ "line": " self.collision_pairs=[]\n",
+ "lineno": 324,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 324,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 325,
+ "end_region_line": 327,
+ "line": " self.collision_dirs={}\n",
+ "lineno": 325,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 325,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 326,
+ "end_region_line": 327,
+ "line": " self.in_collision={'pos':False,'neg':False, 'last_joint_cfg_thresh':1000}\n",
+ "lineno": 326,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 326,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 327,
+ "end_region_line": 327,
+ "line": " self.was_in_collision = {'pos': False, 'neg': False}\n",
+ "lineno": 327,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 327,
+ "start_region_line": 321
+ },
+ {
+ "end_outermost_loop": 328,
+ "end_region_line": 352,
+ "line": "\n",
+ "lineno": 328,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 328,
+ "start_region_line": 320
+ },
+ {
+ "end_outermost_loop": 331,
+ "end_region_line": 331,
+ "line": " def add_collision_pair(self,motion_dir, collision_pair):\n",
+ "lineno": 329,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 329,
+ "start_region_line": 329
+ },
+ {
+ "end_outermost_loop": 330,
+ "end_region_line": 331,
+ "line": " self.collision_pairs.append(collision_pair)\n",
+ "lineno": 330,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 330,
+ "start_region_line": 329
+ },
+ {
+ "end_outermost_loop": 331,
+ "end_region_line": 331,
+ "line": " self.collision_dirs[collision_pair.name]=motion_dir\n",
+ "lineno": 331,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 331,
+ "start_region_line": 329
+ },
+ {
+ "end_outermost_loop": 332,
+ "end_region_line": 352,
+ "line": " \n",
+ "lineno": 332,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 332,
+ "start_region_line": 320
+ },
+ {
+ "end_outermost_loop": 334,
+ "end_region_line": 334,
+ "line": " def update_last_joint_cfg_thresh(self,thresh):\n",
+ "lineno": 333,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 333,
+ "start_region_line": 333
+ },
+ {
+ "end_outermost_loop": 334,
+ "end_region_line": 334,
+ "line": " self.in_collision['last_joint_cfg_thresh'] = thresh\n",
+ "lineno": 334,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 334,
+ "start_region_line": 333
+ },
+ {
+ "end_outermost_loop": 335,
+ "end_region_line": 352,
+ "line": "\n",
+ "lineno": 335,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 335,
+ "start_region_line": 320
+ },
+ {
+ "end_outermost_loop": 336,
+ "end_region_line": 352,
+ "line": "\n",
+ "lineno": 336,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 336,
+ "start_region_line": 320
+ },
+ {
+ "end_outermost_loop": 342,
+ "end_region_line": 342,
+ "line": " def update_collision_pair_min_dist(self,pair_name):\n",
+ "lineno": 337,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 337,
+ "start_region_line": 337
+ },
+ {
+ "end_outermost_loop": 342,
+ "end_region_line": 342,
+ "line": " for cp in self.collision_pairs:\n",
+ "lineno": 338,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 338,
+ "start_region_line": 338
+ },
+ {
+ "end_outermost_loop": 342,
+ "end_region_line": 342,
+ "line": " if cp.name == pair_name:\n",
+ "lineno": 339,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 338,
+ "start_region_line": 338
+ },
+ {
+ "end_outermost_loop": 342,
+ "end_region_line": 342,
+ "line": " _,dist = closest_pair_3d(cp.link_cube.pose,cp.link_pts.pose)\n",
+ "lineno": 340,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 338,
+ "start_region_line": 338
+ },
+ {
+ "end_outermost_loop": 342,
+ "end_region_line": 342,
+ "line": " self.in_collision['las_cp_min_dist'] = {'pair_name':pair_name,'dist':dist}\n",
+ "lineno": 341,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 338,
+ "start_region_line": 338
+ },
+ {
+ "end_outermost_loop": 342,
+ "end_region_line": 342,
+ "line": " return\n",
+ "lineno": 342,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 338,
+ "start_region_line": 338
+ },
+ {
+ "end_outermost_loop": 343,
+ "end_region_line": 352,
+ "line": "\n",
+ "lineno": 343,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 343,
+ "start_region_line": 320
+ },
+ {
+ "end_outermost_loop": 352,
+ "end_region_line": 352,
+ "line": " def pretty_print(self):\n",
+ "lineno": 344,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 344,
+ "start_region_line": 344
+ },
+ {
+ "end_outermost_loop": 345,
+ "end_region_line": 352,
+ "line": " print('-------Collision Joint: %s-----------------'%self.name)\n",
+ "lineno": 345,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 345,
+ "start_region_line": 344
+ },
+ {
+ "end_outermost_loop": 348,
+ "end_region_line": 348,
+ "line": " for cp in self.collision_pairs:\n",
+ "lineno": 346,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 346,
+ "start_region_line": 346
+ },
+ {
+ "end_outermost_loop": 348,
+ "end_region_line": 348,
+ "line": " cp.pretty_print()\n",
+ "lineno": 347,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 346,
+ "start_region_line": 346
+ },
+ {
+ "end_outermost_loop": 348,
+ "end_region_line": 348,
+ "line": " print('Motion dir: %s'%self.collision_dirs[cp.name])\n",
+ "lineno": 348,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 346,
+ "start_region_line": 346
+ },
+ {
+ "end_outermost_loop": 349,
+ "end_region_line": 352,
+ "line": " print('--Active Collisions--')\n",
+ "lineno": 349,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 349,
+ "start_region_line": 344
+ },
+ {
+ "end_outermost_loop": 350,
+ "end_region_line": 352,
+ "line": " print(self.active_collisions)\n",
+ "lineno": 350,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 350,
+ "start_region_line": 344
+ },
+ {
+ "end_outermost_loop": 352,
+ "end_region_line": 352,
+ "line": " for ac in self.active_collisions:\n",
+ "lineno": 351,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 351,
+ "start_region_line": 351
+ },
+ {
+ "end_outermost_loop": 352,
+ "end_region_line": 352,
+ "line": " print('Active Collision: %s' % ac)\n",
+ "lineno": 352,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 351,
+ "start_region_line": 351
+ },
+ {
+ "end_outermost_loop": 353,
+ "end_region_line": 353,
+ "line": "\n",
+ "lineno": 353,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 353,
+ "start_region_line": 353
+ },
+ {
+ "end_outermost_loop": 367,
+ "end_region_line": 367,
+ "line": "def _collision_compute_worker(name, shared_is_running, shared_joint_cfg, shared_collision_status, shared_joint_cfg_thresh, exit_event):\n",
+ "lineno": 354,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 354,
+ "start_region_line": 354
+ },
+ {
+ "end_outermost_loop": 355,
+ "end_region_line": 367,
+ "line": " collision_compute = RobotCollisionCompute(name)\n",
+ "lineno": 355,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 355,
+ "start_region_line": 354
+ },
+ {
+ "end_outermost_loop": 356,
+ "end_region_line": 367,
+ "line": " collision_compute.startup()\n",
+ "lineno": 356,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 356,
+ "start_region_line": 354
+ },
+ {
+ "end_outermost_loop": 357,
+ "end_region_line": 367,
+ "line": " collision_joints_status = {}\n",
+ "lineno": 357,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 357,
+ "start_region_line": 354
+ },
+ {
+ "end_outermost_loop": 358,
+ "end_region_line": 367,
+ "line": " time.sleep(0.5)\n",
+ "lineno": 358,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 358,
+ "start_region_line": 354
+ },
+ {
+ "end_outermost_loop": 367,
+ "end_region_line": 367,
+ "line": " while not exit_event.is_set():\n",
+ "lineno": 359,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 359,
+ "start_region_line": 359
+ },
+ {
+ "end_outermost_loop": 367,
+ "end_region_line": 367,
+ "line": " try:\n",
+ "lineno": 360,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 359,
+ "start_region_line": 359
+ },
+ {
+ "end_outermost_loop": 367,
+ "end_region_line": 367,
+ "line": " if shared_is_running.value:\n",
+ "lineno": 361,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 359,
+ "start_region_line": 359
+ },
+ {
+ "end_outermost_loop": 367,
+ "end_region_line": 367,
+ "line": " collision_compute.step(shared_joint_cfg, shared_joint_cfg_thresh)\n",
+ "lineno": 362,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 359,
+ "start_region_line": 359
+ },
+ {
+ "end_outermost_loop": 367,
+ "end_region_line": 364,
+ "line": " for joint_name in collision_compute.collision_joints:\n",
+ "lineno": 363,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 359,
+ "start_region_line": 363
+ },
+ {
+ "end_outermost_loop": 367,
+ "end_region_line": 364,
+ "line": " collision_joints_status[joint_name] = collision_compute.collision_joints[joint_name].in_collision\n",
+ "lineno": 364,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 359,
+ "start_region_line": 363
+ },
+ {
+ "end_outermost_loop": 367,
+ "end_region_line": 367,
+ "line": " shared_collision_status.put(collision_joints_status)\n",
+ "lineno": 365,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 359,
+ "start_region_line": 359
+ },
+ {
+ "end_outermost_loop": 367,
+ "end_region_line": 367,
+ "line": " except (BrokenPipeError,ConnectionResetError):\n",
+ "lineno": 366,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 359,
+ "start_region_line": 359
+ },
+ {
+ "end_outermost_loop": 367,
+ "end_region_line": 367,
+ "line": " pass\n",
+ "lineno": 367,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 359,
+ "start_region_line": 359
+ },
+ {
+ "end_outermost_loop": 368,
+ "end_region_line": 368,
+ "line": " \n",
+ "lineno": 368,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 368,
+ "start_region_line": 368
+ },
+ {
+ "end_outermost_loop": 476,
+ "end_region_line": 476,
+ "line": "class RobotCollisionMgmt(Device):\n",
+ "lineno": 369,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 369,
+ "start_region_line": 369
+ },
+ {
+ "end_outermost_loop": 390,
+ "end_region_line": 390,
+ "line": " def __init__(self,robot,name='robot_collision_mgmt'):\n",
+ "lineno": 370,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 370,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 371,
+ "end_region_line": 390,
+ "line": " self.name = name\n",
+ "lineno": 371,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 371,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 372,
+ "end_region_line": 390,
+ "line": " self.robot = robot\n",
+ "lineno": 372,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 372,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 373,
+ "end_region_line": 390,
+ "line": " self.shared_joint_cfg = multiprocessing.Queue()\n",
+ "lineno": 373,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 373,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 374,
+ "end_region_line": 390,
+ "line": " self.shared_collision_status = multiprocessing.Queue()\n",
+ "lineno": 374,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 374,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 375,
+ "end_region_line": 390,
+ "line": " self.shared_joint_cfg_thresh = multiprocessing.Value(ctypes.c_float, 1000.0)\n",
+ "lineno": 375,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 375,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 376,
+ "end_region_line": 390,
+ "line": " self.shared_is_running = multiprocessing.Value(ctypes.c_bool, False)\n",
+ "lineno": 376,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 376,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 377,
+ "end_region_line": 390,
+ "line": " self.exit_event = multiprocessing.Event()\n",
+ "lineno": 377,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 377,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 378,
+ "end_region_line": 390,
+ "line": " signal.signal(signal.SIGINT, self.signal_handler)\n",
+ "lineno": 378,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 378,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 379,
+ "end_region_line": 390,
+ "line": " signal.signal(signal.SIGTERM, self.signal_handler)\n",
+ "lineno": 379,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 379,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 380,
+ "end_region_line": 390,
+ "line": " self.collision_compute_proccess = multiprocessing.Process(target=_collision_compute_worker,\n",
+ "lineno": 380,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 380,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 381,
+ "end_region_line": 390,
+ "line": " name=name,\n",
+ "lineno": 381,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 381,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 382,
+ "end_region_line": 390,
+ "line": " args=(self.name,\n",
+ "lineno": 382,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 382,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 383,
+ "end_region_line": 390,
+ "line": " self.shared_is_running,\n",
+ "lineno": 383,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 383,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 384,
+ "end_region_line": 390,
+ "line": " self.shared_joint_cfg,\n",
+ "lineno": 384,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 384,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 385,
+ "end_region_line": 390,
+ "line": " self.shared_collision_status,\n",
+ "lineno": 385,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 385,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 386,
+ "end_region_line": 390,
+ "line": " self.shared_joint_cfg_thresh,\n",
+ "lineno": 386,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 386,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 387,
+ "end_region_line": 390,
+ "line": " self.exit_event,),daemon=True)\n",
+ "lineno": 387,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 387,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 388,
+ "end_region_line": 390,
+ "line": " self.running = False\n",
+ "lineno": 388,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 388,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 389,
+ "end_region_line": 390,
+ "line": " self.robot_params = RobotParams().get_params()[1]\n",
+ "lineno": 389,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 389,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 390,
+ "end_region_line": 390,
+ "line": " self.collision_status = {}\n",
+ "lineno": 390,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 390,
+ "start_region_line": 370
+ },
+ {
+ "end_outermost_loop": 391,
+ "end_region_line": 476,
+ "line": "\n",
+ "lineno": 391,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 391,
+ "start_region_line": 369
+ },
+ {
+ "end_outermost_loop": 393,
+ "end_region_line": 393,
+ "line": " def startup(self):\n",
+ "lineno": 392,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 392,
+ "start_region_line": 392
+ },
+ {
+ "end_outermost_loop": 393,
+ "end_region_line": 393,
+ "line": " self.collision_compute_proccess.start()\n",
+ "lineno": 393,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 393,
+ "start_region_line": 392
+ },
+ {
+ "end_outermost_loop": 394,
+ "end_region_line": 476,
+ "line": " \n",
+ "lineno": 394,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 394,
+ "start_region_line": 369
+ },
+ {
+ "end_outermost_loop": 399,
+ "end_region_line": 399,
+ "line": " def stop(self):\n",
+ "lineno": 395,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 395,
+ "start_region_line": 395
+ },
+ {
+ "end_outermost_loop": 396,
+ "end_region_line": 399,
+ "line": " self.exit_event.set()\n",
+ "lineno": 396,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 396,
+ "start_region_line": 395
+ },
+ {
+ "end_outermost_loop": 397,
+ "end_region_line": 399,
+ "line": " self.shared_is_running.set(False)\n",
+ "lineno": 397,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 397,
+ "start_region_line": 395
+ },
+ {
+ "end_outermost_loop": 398,
+ "end_region_line": 399,
+ "line": " self.collision_compute_proccess.terminate()\n",
+ "lineno": 398,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 398,
+ "start_region_line": 395
+ },
+ {
+ "end_outermost_loop": 399,
+ "end_region_line": 399,
+ "line": " self.collision_compute_proccess.join()\n",
+ "lineno": 399,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 399,
+ "start_region_line": 395
+ },
+ {
+ "end_outermost_loop": 400,
+ "end_region_line": 476,
+ "line": " \n",
+ "lineno": 400,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 400,
+ "start_region_line": 369
+ },
+ {
+ "end_outermost_loop": 411,
+ "end_region_line": 411,
+ "line": " def step(self):\n",
+ "lineno": 401,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 401,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 402,
+ "end_region_line": 411,
+ "line": " try:\n",
+ "lineno": 402,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 402,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 403,
+ "end_region_line": 411,
+ "line": " self.shared_is_running.value = self.running\n",
+ "lineno": 403,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 403,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 409,
+ "end_region_line": 411,
+ "line": " if self.running:\n",
+ "lineno": 404,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 404,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 405,
+ "end_region_line": 411,
+ "line": " self.shared_joint_cfg_thresh.value = self.get_normalized_cfg_threshold()\n",
+ "lineno": 405,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 405,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 406,
+ "end_region_line": 411,
+ "line": " self.shared_joint_cfg.put(self.get_joint_configuration(braked=True))\n",
+ "lineno": 406,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 406,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 407,
+ "end_region_line": 411,
+ "line": " self.collision_status.update(self.shared_collision_status.get())\n",
+ "lineno": 407,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 407,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 408,
+ "end_region_line": 409,
+ "line": " for j in self.collision_status.keys():\n",
+ "lineno": 408,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 408,
+ "start_region_line": 408
+ },
+ {
+ "end_outermost_loop": 409,
+ "end_region_line": 409,
+ "line": " self.get_joint_motor(j).step_collision_avoidance(self.collision_status[j])\n",
+ "lineno": 409,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 409,
+ "start_region_line": 408
+ },
+ {
+ "end_outermost_loop": 410,
+ "end_region_line": 411,
+ "line": " except (BrokenPipeError,ConnectionResetError):\n",
+ "lineno": 410,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 410,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 411,
+ "end_region_line": 411,
+ "line": " pass\n",
+ "lineno": 411,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 411,
+ "start_region_line": 401
+ },
+ {
+ "end_outermost_loop": 412,
+ "end_region_line": 476,
+ "line": "\n",
+ "lineno": 412,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 412,
+ "start_region_line": 369
+ },
+ {
+ "end_outermost_loop": 414,
+ "end_region_line": 414,
+ "line": " def signal_handler(self, signal_received, frame):\n",
+ "lineno": 413,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 413,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 414,
+ "end_region_line": 414,
+ "line": " self.exit_event.set()\n",
+ "lineno": 414,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 414,
+ "start_region_line": 413
+ },
+ {
+ "end_outermost_loop": 415,
+ "end_region_line": 476,
+ "line": " \n",
+ "lineno": 415,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 415,
+ "start_region_line": 369
+ },
+ {
+ "end_outermost_loop": 426,
+ "end_region_line": 426,
+ "line": " def get_joint_motor(self,joint_name):\n",
+ "lineno": 416,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 416,
+ "start_region_line": 416
+ },
+ {
+ "end_outermost_loop": 418,
+ "end_region_line": 426,
+ "line": " if joint_name=='lift':\n",
+ "lineno": 417,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 417,
+ "start_region_line": 416
+ },
+ {
+ "end_outermost_loop": 418,
+ "end_region_line": 426,
+ "line": " return self.robot.lift\n",
+ "lineno": 418,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 418,
+ "start_region_line": 416
+ },
+ {
+ "end_outermost_loop": 420,
+ "end_region_line": 426,
+ "line": " if joint_name=='arm':\n",
+ "lineno": 419,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 419,
+ "start_region_line": 416
+ },
+ {
+ "end_outermost_loop": 420,
+ "end_region_line": 426,
+ "line": " return self.robot.arm\n",
+ "lineno": 420,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 420,
+ "start_region_line": 416
+ },
+ {
+ "end_outermost_loop": 422,
+ "end_region_line": 426,
+ "line": " if joint_name=='head_pan':\n",
+ "lineno": 421,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 421,
+ "start_region_line": 416
+ },
+ {
+ "end_outermost_loop": 422,
+ "end_region_line": 426,
+ "line": " return self.robot.head.get_joint('head_pan')\n",
+ "lineno": 422,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 422,
+ "start_region_line": 416
+ },
+ {
+ "end_outermost_loop": 424,
+ "end_region_line": 426,
+ "line": " if joint_name=='head_tilt':\n",
+ "lineno": 423,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 423,
+ "start_region_line": 416
+ },
+ {
+ "end_outermost_loop": 424,
+ "end_region_line": 426,
+ "line": " return self.robot.head.get_joint('head_tilt')\n",
+ "lineno": 424,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 424,
+ "start_region_line": 416
+ },
+ {
+ "end_outermost_loop": 426,
+ "end_region_line": 426,
+ "line": " #Try the tool\n",
+ "lineno": 425,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 416,
+ "start_region_line": 416
+ },
+ {
+ "end_outermost_loop": 426,
+ "end_region_line": 426,
+ "line": " return self.robot.end_of_arm.get_joint(joint_name)\n",
+ "lineno": 426,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 426,
+ "start_region_line": 416
+ },
+ {
+ "end_outermost_loop": 427,
+ "end_region_line": 476,
+ "line": "\n",
+ "lineno": 427,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 427,
+ "start_region_line": 369
+ },
+ {
+ "end_outermost_loop": 440,
+ "end_region_line": 440,
+ "line": " def get_normalized_cfg_threshold(self):\n",
+ "lineno": 428,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 428,
+ "start_region_line": 428
+ },
+ {
+ "end_outermost_loop": 429,
+ "end_region_line": 440,
+ "line": " arm_pos = self.robot.status['arm']['pos']/(0.5)\n",
+ "lineno": 429,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 429,
+ "start_region_line": 428
+ },
+ {
+ "end_outermost_loop": 430,
+ "end_region_line": 440,
+ "line": " lift_pos = self.robot.status['lift']['pos']/(1.1)\n",
+ "lineno": 430,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 430,
+ "start_region_line": 428
+ },
+ {
+ "end_outermost_loop": 431,
+ "end_region_line": 440,
+ "line": " head_pan_pos = (self.robot.status['head']['head_pan']['pos_ticks']- self.robot_params['head_pan']['range_t'][0])/(self.robot_params['head_pan']['range_t'][1] - self.robot_params['head_pan']['range_t'][0])\n",
+ "lineno": 431,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 431,
+ "start_region_line": 428
+ },
+ {
+ "end_outermost_loop": 432,
+ "end_region_line": 440,
+ "line": " head_tilt_pos = (self.robot.status['head']['head_tilt']['pos_ticks']- self.robot_params['head_tilt']['range_t'][0])/(self.robot_params['head_tilt']['range_t'][1] - self.robot_params['head_tilt']['range_t'][0])\n",
+ "lineno": 432,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 432,
+ "start_region_line": 428
+ },
+ {
+ "end_outermost_loop": 433,
+ "end_region_line": 440,
+ "line": " thresh = arm_pos + lift_pos + head_pan_pos + head_tilt_pos\n",
+ "lineno": 433,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 433,
+ "start_region_line": 428
+ },
+ {
+ "end_outermost_loop": 434,
+ "end_region_line": 440,
+ "line": " i = 0\n",
+ "lineno": 434,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 434,
+ "start_region_line": 428
+ },
+ {
+ "end_outermost_loop": 438,
+ "end_region_line": 438,
+ "line": " for j in self.robot.end_of_arm.joints:\n",
+ "lineno": 435,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 435,
+ "start_region_line": 435
+ },
+ {
+ "end_outermost_loop": 438,
+ "end_region_line": 438,
+ "line": " value = (self.robot.status['end_of_arm'][j]['pos_ticks']- self.robot_params[j]['range_t'][0])/(self.robot_params['head_pan']['range_t'][1] - self.robot_params[j]['range_t'][0])\n",
+ "lineno": 436,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 435,
+ "start_region_line": 435
+ },
+ {
+ "end_outermost_loop": 438,
+ "end_region_line": 438,
+ "line": " thresh = thresh + value\n",
+ "lineno": 437,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 435,
+ "start_region_line": 435
+ },
+ {
+ "end_outermost_loop": 438,
+ "end_region_line": 438,
+ "line": " i = i + 1\n",
+ "lineno": 438,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 435,
+ "start_region_line": 435
+ },
+ {
+ "end_outermost_loop": 439,
+ "end_region_line": 440,
+ "line": " thresh = thresh/(4+i)\n",
+ "lineno": 439,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 439,
+ "start_region_line": 428
+ },
+ {
+ "end_outermost_loop": 440,
+ "end_region_line": 440,
+ "line": " return float(thresh)\n",
+ "lineno": 440,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 440,
+ "start_region_line": 428
+ },
+ {
+ "end_outermost_loop": 441,
+ "end_region_line": 476,
+ "line": " \n",
+ "lineno": 441,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 441,
+ "start_region_line": 369
+ },
+ {
+ "end_outermost_loop": 470,
+ "end_region_line": 470,
+ "line": " def get_joint_configuration(self,braked=False):\n",
+ "lineno": 442,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 442,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 443,
+ "end_region_line": 470,
+ "line": " \"\"\"\n",
+ "lineno": 443,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 443,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 444,
+ "end_region_line": 470,
+ "line": " Construct a dictionary of robot's current pose\n",
+ "lineno": 444,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 444,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 445,
+ "end_region_line": 470,
+ "line": " \"\"\"\n",
+ "lineno": 445,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 445,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 446,
+ "end_region_line": 470,
+ "line": " s = self.robot.get_status()\n",
+ "lineno": 446,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 446,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 447,
+ "end_region_line": 470,
+ "line": " kbd = self.robot_params['robot_collision_mgmt'][self.robot.params['model_name']]['k_brake_distance']\n",
+ "lineno": 447,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 447,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 457,
+ "end_region_line": 470,
+ "line": " if braked:\n",
+ "lineno": 448,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 448,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 449,
+ "end_region_line": 470,
+ "line": " da=kbd['arm']*self.robot.arm.get_braking_distance()/4.0\n",
+ "lineno": 449,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 449,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 450,
+ "end_region_line": 470,
+ "line": " dl=kbd['lift']*self.robot.lift.get_braking_distance()\n",
+ "lineno": 450,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 450,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 451,
+ "end_region_line": 470,
+ "line": " dhp = kbd['head_pan'] * self.robot.head.get_joint('head_pan').get_braking_distance()\n",
+ "lineno": 451,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 451,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 452,
+ "end_region_line": 470,
+ "line": " dht = kbd['head_tilt'] * self.robot.head.get_joint('head_tilt').get_braking_distance()\n",
+ "lineno": 452,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 452,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 457,
+ "end_region_line": 470,
+ "line": " else:\n",
+ "lineno": 453,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 448,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 454,
+ "end_region_line": 470,
+ "line": " da=0.0\n",
+ "lineno": 454,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 454,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 455,
+ "end_region_line": 470,
+ "line": " dl=0.0\n",
+ "lineno": 455,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 455,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 456,
+ "end_region_line": 470,
+ "line": " dhp=0.0\n",
+ "lineno": 456,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 456,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 457,
+ "end_region_line": 470,
+ "line": " dht=0.0\n",
+ "lineno": 457,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 457,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 458,
+ "end_region_line": 470,
+ "line": "\n",
+ "lineno": 458,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 458,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 459,
+ "end_region_line": 470,
+ "line": " configuration = {\n",
+ "lineno": 459,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 459,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 460,
+ "end_region_line": 470,
+ "line": " 'joint_lift': dl+s['lift']['pos'],\n",
+ "lineno": 460,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 460,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 461,
+ "end_region_line": 470,
+ "line": " 'joint_arm_l0': da+s['arm']['pos']/4.0,\n",
+ "lineno": 461,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 461,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 462,
+ "end_region_line": 470,
+ "line": " 'joint_arm_l1': da+s['arm']['pos']/4.0,\n",
+ "lineno": 462,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 462,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 463,
+ "end_region_line": 470,
+ "line": " 'joint_arm_l2': da+s['arm']['pos']/4.0,\n",
+ "lineno": 463,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 463,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 464,
+ "end_region_line": 470,
+ "line": " 'joint_arm_l3': da+s['arm']['pos']/4.0,\n",
+ "lineno": 464,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 464,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 465,
+ "end_region_line": 470,
+ "line": " 'joint_head_pan': dhp+s['head']['head_pan']['pos'],\n",
+ "lineno": 465,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 465,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 466,
+ "end_region_line": 470,
+ "line": " 'joint_head_tilt': dht+s['head']['head_tilt']['pos']\n",
+ "lineno": 466,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 466,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 467,
+ "end_region_line": 470,
+ "line": " }\n",
+ "lineno": 467,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 467,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 468,
+ "end_region_line": 470,
+ "line": "\n",
+ "lineno": 468,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 468,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 469,
+ "end_region_line": 470,
+ "line": " configuration.update(self.robot.end_of_arm.get_joint_configuration(braked))\n",
+ "lineno": 469,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 469,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 470,
+ "end_region_line": 470,
+ "line": " return configuration\n",
+ "lineno": 470,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 470,
+ "start_region_line": 442
+ },
+ {
+ "end_outermost_loop": 471,
+ "end_region_line": 476,
+ "line": " \n",
+ "lineno": 471,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 471,
+ "start_region_line": 369
+ },
+ {
+ "end_outermost_loop": 473,
+ "end_region_line": 473,
+ "line": " def enable(self):\n",
+ "lineno": 472,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 472,
+ "start_region_line": 472
+ },
+ {
+ "end_outermost_loop": 473,
+ "end_region_line": 473,
+ "line": " self.running=True\n",
+ "lineno": 473,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 473,
+ "start_region_line": 472
+ },
+ {
+ "end_outermost_loop": 474,
+ "end_region_line": 476,
+ "line": "\n",
+ "lineno": 474,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 474,
+ "start_region_line": 369
+ },
+ {
+ "end_outermost_loop": 476,
+ "end_region_line": 476,
+ "line": " def disable(self):\n",
+ "lineno": 475,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 475,
+ "start_region_line": 475
+ },
+ {
+ "end_outermost_loop": 476,
+ "end_region_line": 476,
+ "line": " self.running=False\n",
+ "lineno": 476,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 476,
+ "start_region_line": 475
+ },
+ {
+ "end_outermost_loop": 477,
+ "end_region_line": 477,
+ "line": "\n",
+ "lineno": 477,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 477,
+ "start_region_line": 477
+ },
+ {
+ "end_outermost_loop": 651,
+ "end_region_line": 651,
+ "line": "class RobotCollisionCompute(Device):\n",
+ "lineno": 478,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 478,
+ "start_region_line": 478
+ },
+ {
+ "end_outermost_loop": 499,
+ "end_region_line": 499,
+ "line": " def __init__(self,name='robot_collision_mgmt'):\n",
+ "lineno": 479,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 479,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 480,
+ "end_region_line": 499,
+ "line": " \"\"\"\n",
+ "lineno": 480,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 480,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 481,
+ "end_region_line": 499,
+ "line": " RobotCollisionMgmt monitors for collisions between links.\n",
+ "lineno": 481,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 481,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 482,
+ "end_region_line": 499,
+ "line": " It utilizes the Collision mesh for collision estimation.\n",
+ "lineno": 482,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 482,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 483,
+ "end_region_line": 499,
+ "line": " Given the Cartesian structure of Stretch we simplify the collision detection in order to achieve real-time speeds.\n",
+ "lineno": 483,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 483,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 484,
+ "end_region_line": 499,
+ "line": " We simplify the problem by assuming:\n",
+ "lineno": 484,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 484,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 485,
+ "end_region_line": 499,
+ "line": " * One of the collision meshes (\"cube\") is a cube that is aligned with XYZ axis (eg AABB)\n",
+ "lineno": 485,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 485,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 486,
+ "end_region_line": 499,
+ "line": " * The other collision mesh (\"pts\") is simple shape of just a few points (eg, a cube, trapezoid, etc)\\u003cmax_mesh_points\n",
+ "lineno": 486,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 486,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 487,
+ "end_region_line": 499,
+ "line": "\n",
+ "lineno": 487,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 487,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 488,
+ "end_region_line": 499,
+ "line": " The params define which links we want to monitor collisions between.\n",
+ "lineno": 488,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 488,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 489,
+ "end_region_line": 499,
+ "line": " Each link includes a parameter \"scale_pct\" which allows the mesh size to be expanded by a percentage around its centroid\n",
+ "lineno": 489,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 489,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 490,
+ "end_region_line": 499,
+ "line": " enabling the ability to increase the safety zone.\n",
+ "lineno": 490,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 490,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 491,
+ "end_region_line": 499,
+ "line": " \"\"\"\n",
+ "lineno": 491,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 491,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 492,
+ "end_region_line": 499,
+ "line": " Device.__init__(self, name)\n",
+ "lineno": 492,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 492,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 493,
+ "end_region_line": 499,
+ "line": " self.collision_joints = {}\n",
+ "lineno": 493,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 493,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 494,
+ "end_region_line": 499,
+ "line": " self.collision_links = {}\n",
+ "lineno": 494,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 494,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 495,
+ "end_region_line": 499,
+ "line": " self.collision_pairs = {}\n",
+ "lineno": 495,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 495,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 496,
+ "end_region_line": 499,
+ "line": " chime.theme('big-sur') #'material')\n",
+ "lineno": 496,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 496,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 497,
+ "end_region_line": 499,
+ "line": " self.urdf=None\n",
+ "lineno": 497,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 497,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 498,
+ "end_region_line": 499,
+ "line": " self.prev_loop_start_ts = None\n",
+ "lineno": 498,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 498,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 499,
+ "end_region_line": 499,
+ "line": " self.robot_params = RobotParams().get_params()[1]\n",
+ "lineno": 499,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 499,
+ "start_region_line": 479
+ },
+ {
+ "end_outermost_loop": 500,
+ "end_region_line": 651,
+ "line": "\n",
+ "lineno": 500,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 500,
+ "start_region_line": 478
+ },
+ {
+ "end_outermost_loop": 503,
+ "end_region_line": 503,
+ "line": " def pretty_print(self):\n",
+ "lineno": 501,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 501,
+ "start_region_line": 501
+ },
+ {
+ "end_outermost_loop": 503,
+ "end_region_line": 503,
+ "line": " for j in self.collision_joints:\n",
+ "lineno": 502,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 502,
+ "start_region_line": 502
+ },
+ {
+ "end_outermost_loop": 503,
+ "end_region_line": 503,
+ "line": " self.collision_joints[j].pretty_print()\n",
+ "lineno": 503,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 502,
+ "start_region_line": 502
+ },
+ {
+ "end_outermost_loop": 504,
+ "end_region_line": 651,
+ "line": "\n",
+ "lineno": 504,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 504,
+ "start_region_line": 478
+ },
+ {
+ "end_outermost_loop": 505,
+ "end_region_line": 651,
+ "line": "\n",
+ "lineno": 505,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 505,
+ "start_region_line": 478
+ },
+ {
+ "end_outermost_loop": 506,
+ "end_region_line": 651,
+ "line": " \n",
+ "lineno": 506,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 506,
+ "start_region_line": 478
+ },
+ {
+ "end_outermost_loop": 562,
+ "end_region_line": 562,
+ "line": " def startup(self,threaded=False):\n",
+ "lineno": 507,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 507,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 508,
+ "end_region_line": 562,
+ "line": " Device.startup(self, threaded)\n",
+ "lineno": 508,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 508,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 509,
+ "end_region_line": 562,
+ "line": " pkg = str(importlib_resources.files(\"stretch_urdf\")) # .local/lib/python3.10/site-packages/stretch_urdf)\n",
+ "lineno": 509,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 509,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 510,
+ "end_region_line": 562,
+ "line": " model_name = self.robot_params['robot']['model_name']\n",
+ "lineno": 510,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 510,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 511,
+ "end_region_line": 562,
+ "line": " eoa_name= self.robot_params['robot']['tool']\n",
+ "lineno": 511,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 511,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 512,
+ "end_region_line": 562,
+ "line": " urdf_name = pkg + '/%s/stretch_description_%s_%s.urdf' % (model_name, model_name, eoa_name)\n",
+ "lineno": 512,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 512,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 513,
+ "end_region_line": 562,
+ "line": " mesh_path = pkg + '/%s/' % (model_name)\n",
+ "lineno": 513,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 513,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 514,
+ "end_region_line": 562,
+ "line": "\n",
+ "lineno": 514,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 514,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 518,
+ "end_region_line": 562,
+ "line": " if self.params[model_name]=={}:\n",
+ "lineno": 515,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 515,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 518,
+ "end_region_line": 562,
+ "line": " #self.logger.warning('Collision parameters not present. Disabling collision system.')\n",
+ "lineno": 516,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 515,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 517,
+ "end_region_line": 562,
+ "line": " self.running = False\n",
+ "lineno": 517,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 517,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 518,
+ "end_region_line": 562,
+ "line": " return\n",
+ "lineno": 518,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 518,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 519,
+ "end_region_line": 562,
+ "line": "\n",
+ "lineno": 519,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 519,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 520,
+ "end_region_line": 562,
+ "line": " try:\n",
+ "lineno": 520,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 520,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 521,
+ "end_region_line": 562,
+ "line": " self.urdf = urdf_loader.URDF.load(urdf_name)\n",
+ "lineno": 521,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 521,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 522,
+ "end_region_line": 562,
+ "line": " except ValueError:\n",
+ "lineno": 522,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 522,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 523,
+ "end_region_line": 562,
+ "line": " print('Unable to load URDF: %s. Disabling collision system.' % urdf_name)\n",
+ "lineno": 523,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 523,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 524,
+ "end_region_line": 562,
+ "line": " self.urdf = None\n",
+ "lineno": 524,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 524,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 525,
+ "end_region_line": 562,
+ "line": " self.running = False\n",
+ "lineno": 525,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 525,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 526,
+ "end_region_line": 562,
+ "line": " return\n",
+ "lineno": 526,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 526,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 527,
+ "end_region_line": 562,
+ "line": "\n",
+ "lineno": 527,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 527,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 562,
+ "end_region_line": 562,
+ "line": " #Construct collision pairs\n",
+ "lineno": 528,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 507,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 529,
+ "end_region_line": 562,
+ "line": " cp_dict = self.params[model_name]['collision_pairs']\n",
+ "lineno": 529,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 529,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 530,
+ "end_region_line": 562,
+ "line": " cp_dict.update(self.robot_params[eoa_name]['collision_mgmt']['collision_pairs'])\n",
+ "lineno": 530,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 530,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 531,
+ "end_region_line": 562,
+ "line": "\n",
+ "lineno": 531,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 531,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 543,
+ "end_region_line": 543,
+ "line": " for cp_name in cp_dict:\n",
+ "lineno": 532,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 532,
+ "start_region_line": 532
+ },
+ {
+ "end_outermost_loop": 543,
+ "end_region_line": 543,
+ "line": " cp=cp_dict[cp_name] #Eg {'link_pts': 'link_head_tilt', 'link_cube': 'link_arm_l4','detect_as':'pts'}\n",
+ "lineno": 533,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 532,
+ "start_region_line": 532
+ },
+ {
+ "end_outermost_loop": 543,
+ "end_region_line": 543,
+ "line": " if cp['link_pts'] not in self.collision_links:\n",
+ "lineno": 534,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 532,
+ "start_region_line": 532
+ },
+ {
+ "end_outermost_loop": 543,
+ "end_region_line": 543,
+ "line": " self.collision_links[cp['link_pts']] = CollisionLink(cp['link_pts'], self.urdf, mesh_path,\n",
+ "lineno": 535,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 532,
+ "start_region_line": 532
+ },
+ {
+ "end_outermost_loop": 543,
+ "end_region_line": 543,
+ "line": " self.params['max_mesh_points'])\n",
+ "lineno": 536,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 532,
+ "start_region_line": 532
+ },
+ {
+ "end_outermost_loop": 543,
+ "end_region_line": 543,
+ "line": " if cp['link_cube'] not in self.collision_links:\n",
+ "lineno": 537,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 532,
+ "start_region_line": 532
+ },
+ {
+ "end_outermost_loop": 543,
+ "end_region_line": 543,
+ "line": " self.collision_links[cp['link_cube']] = CollisionLink(cp['link_cube'], self.urdf, mesh_path,\n",
+ "lineno": 538,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 532,
+ "start_region_line": 532
+ },
+ {
+ "end_outermost_loop": 543,
+ "end_region_line": 543,
+ "line": " self.params['max_mesh_points'])\n",
+ "lineno": 539,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 532,
+ "start_region_line": 532
+ },
+ {
+ "end_outermost_loop": 543,
+ "end_region_line": 543,
+ "line": " self.collision_pairs[cp_name] = CollisionPair(name=cp_name,\n",
+ "lineno": 540,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 532,
+ "start_region_line": 532
+ },
+ {
+ "end_outermost_loop": 543,
+ "end_region_line": 543,
+ "line": " link_pts=self.collision_links[cp['link_pts']],\n",
+ "lineno": 541,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 532,
+ "start_region_line": 532
+ },
+ {
+ "end_outermost_loop": 543,
+ "end_region_line": 543,
+ "line": " link_cube=self.collision_links[cp['link_cube']],\n",
+ "lineno": 542,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 532,
+ "start_region_line": 532
+ },
+ {
+ "end_outermost_loop": 543,
+ "end_region_line": 543,
+ "line": " detect_as=cp['detect_as'])\n",
+ "lineno": 543,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 532,
+ "start_region_line": 532
+ },
+ {
+ "end_outermost_loop": 544,
+ "end_region_line": 562,
+ "line": "\n",
+ "lineno": 544,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 544,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 562,
+ "end_region_line": 562,
+ "line": " #Assign collision pairs to each joint\n",
+ "lineno": 545,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 507,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 562,
+ "end_region_line": 562,
+ "line": " #Include those of standard robot body plus its defined tool\n",
+ "lineno": 546,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 507,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 562,
+ "end_region_line": 562,
+ "line": " # EG collision_joints={'lift':[{collision_1},{collision_2...}],'head_pan':[...]}\n",
+ "lineno": 547,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 507,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 548,
+ "end_region_line": 562,
+ "line": " cj_dict=self.params[model_name]['joints']\n",
+ "lineno": 548,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 548,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 549,
+ "end_region_line": 562,
+ "line": " eoa_cj_dict=self.robot_params[eoa_name]['collision_mgmt']['joints']\n",
+ "lineno": 549,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 549,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 550,
+ "end_region_line": 562,
+ "line": "\n",
+ "lineno": 550,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 550,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 555,
+ "end_region_line": 555,
+ "line": " for tt in eoa_cj_dict:\n",
+ "lineno": 551,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 551,
+ "start_region_line": 551
+ },
+ {
+ "end_outermost_loop": 555,
+ "end_region_line": 555,
+ "line": " if tt in cj_dict:\n",
+ "lineno": 552,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 551,
+ "start_region_line": 551
+ },
+ {
+ "end_outermost_loop": 555,
+ "end_region_line": 555,
+ "line": " cj_dict[tt]+=eoa_cj_dict[tt]\n",
+ "lineno": 553,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 551,
+ "start_region_line": 551
+ },
+ {
+ "end_outermost_loop": 555,
+ "end_region_line": 555,
+ "line": " else:\n",
+ "lineno": 554,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 551,
+ "start_region_line": 551
+ },
+ {
+ "end_outermost_loop": 555,
+ "end_region_line": 555,
+ "line": " cj_dict[tt]=eoa_cj_dict[tt]\n",
+ "lineno": 555,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 551,
+ "start_region_line": 551
+ },
+ {
+ "end_outermost_loop": 556,
+ "end_region_line": 562,
+ "line": "\n",
+ "lineno": 556,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 556,
+ "start_region_line": 507
+ },
+ {
+ "end_outermost_loop": 562,
+ "end_region_line": 562,
+ "line": " for joint_name in cj_dict:\n",
+ "lineno": 557,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 557,
+ "start_region_line": 557
+ },
+ {
+ "end_outermost_loop": 562,
+ "end_region_line": 562,
+ "line": " self.collision_joints[joint_name]=CollisionJoint(joint_name)\n",
+ "lineno": 558,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 557,
+ "start_region_line": 557
+ },
+ {
+ "end_outermost_loop": 562,
+ "end_region_line": 562,
+ "line": " cp_list = cj_dict[joint_name]\n",
+ "lineno": 559,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 557,
+ "start_region_line": 557
+ },
+ {
+ "end_outermost_loop": 562,
+ "end_region_line": 562,
+ "line": " for cp in cp_list: #eg cp={'motion_dir': 'pos', 'collision_pair': 'link_head_tilt_TO_link_arm_l4'}\n",
+ "lineno": 560,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 557,
+ "start_region_line": 560
+ },
+ {
+ "end_outermost_loop": 562,
+ "end_region_line": 562,
+ "line": " self.collision_joints[joint_name].add_collision_pair(motion_dir=cp['motion_dir'],\n",
+ "lineno": 561,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 557,
+ "start_region_line": 560
+ },
+ {
+ "end_outermost_loop": 562,
+ "end_region_line": 562,
+ "line": " collision_pair=self.collision_pairs[cp['collision_pair']])\n",
+ "lineno": 562,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 557,
+ "start_region_line": 560
+ },
+ {
+ "end_outermost_loop": 563,
+ "end_region_line": 651,
+ "line": " \n",
+ "lineno": 563,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 563,
+ "start_region_line": 478
+ },
+ {
+ "end_outermost_loop": 564,
+ "end_region_line": 651,
+ "line": "\n",
+ "lineno": 564,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 564,
+ "start_region_line": 478
+ },
+ {
+ "end_outermost_loop": 632,
+ "end_region_line": 632,
+ "line": " def step(self,cfg=None, joint_cfg_thresh=None):\n",
+ "lineno": 565,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 565,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 566,
+ "end_region_line": 632,
+ "line": " \"\"\"\n",
+ "lineno": 566,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 566,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 567,
+ "end_region_line": 632,
+ "line": " Check for interference between cube pairs\n",
+ "lineno": 567,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 567,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 568,
+ "end_region_line": 632,
+ "line": " \"\"\"\n",
+ "lineno": 568,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 568,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 632,
+ "end_region_line": 632,
+ "line": " # if self.prev_loop_start_ts:\n",
+ "lineno": 569,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 565,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 632,
+ "end_region_line": 632,
+ "line": " # print(f\"[{self.name}] Step exec time: {(time.perf_counter()-self.prev_loop_start_ts)*1000}ms\")\n",
+ "lineno": 570,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 565,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 571,
+ "end_region_line": 632,
+ "line": " \n",
+ "lineno": 571,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 571,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 573,
+ "end_region_line": 632,
+ "line": " if self.urdf is None:\n",
+ "lineno": 572,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 572,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 573,
+ "end_region_line": 632,
+ "line": " return\n",
+ "lineno": 573,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 573,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 574,
+ "end_region_line": 632,
+ "line": "\n",
+ "lineno": 574,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 574,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 632,
+ "end_region_line": 632,
+ "line": " # if cfg is None:\n",
+ "lineno": 575,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 565,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 632,
+ "end_region_line": 632,
+ "line": " # cfg = self.get_joint_configuration(braked=True)#_braked()\n",
+ "lineno": 576,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 565,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 577,
+ "end_region_line": 632,
+ "line": "\n",
+ "lineno": 577,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 577,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 632,
+ "end_region_line": 632,
+ "line": " # Update forward kinematics of links\n",
+ "lineno": 578,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 565,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 579,
+ "end_region_line": 632,
+ "line": " _cfg = cfg.get()\n",
+ "lineno": 579,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 579,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 580,
+ "end_region_line": 632,
+ "line": " lfk = self.urdf.link_fk(cfg=_cfg, links=self.collision_links.keys(), use_names=True)\n",
+ "lineno": 580,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 580,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 581,
+ "end_region_line": 632,
+ "line": "\n",
+ "lineno": 581,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 581,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 632,
+ "end_region_line": 632,
+ "line": " # Update poses of links based on fk\n",
+ "lineno": 582,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 565,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 585,
+ "end_region_line": 585,
+ "line": " for link_name in lfk: \n",
+ "lineno": 583,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 583,
+ "start_region_line": 583
+ },
+ {
+ "end_outermost_loop": 585,
+ "end_region_line": 585,
+ "line": " self.collision_links[link_name].set_pose(lfk[link_name].dot(\n",
+ "lineno": 584,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 583,
+ "start_region_line": 583
+ },
+ {
+ "end_outermost_loop": 585,
+ "end_region_line": 585,
+ "line": " self.collision_links[link_name].points.transpose()).transpose())\n",
+ "lineno": 585,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 583,
+ "start_region_line": 583
+ },
+ {
+ "end_outermost_loop": 586,
+ "end_region_line": 632,
+ "line": "\n",
+ "lineno": 586,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 586,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 632,
+ "end_region_line": 632,
+ "line": " # Reset each link / joint status before updating\n",
+ "lineno": 587,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 565,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 590,
+ "end_region_line": 590,
+ "line": " for link_name in self.collision_links:\n",
+ "lineno": 588,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 588,
+ "start_region_line": 588
+ },
+ {
+ "end_outermost_loop": 590,
+ "end_region_line": 590,
+ "line": " self.collision_links[link_name].was_in_collision =self.collision_links[link_name].in_collision\n",
+ "lineno": 589,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 588,
+ "start_region_line": 588
+ },
+ {
+ "end_outermost_loop": 590,
+ "end_region_line": 590,
+ "line": " self.collision_links[link_name].in_collision=False\n",
+ "lineno": 590,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 588,
+ "start_region_line": 588
+ },
+ {
+ "end_outermost_loop": 596,
+ "end_region_line": 596,
+ "line": " for joint_name in self.collision_joints:\n",
+ "lineno": 591,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 591,
+ "start_region_line": 591
+ },
+ {
+ "end_outermost_loop": 596,
+ "end_region_line": 596,
+ "line": " self.collision_joints[joint_name].active_collisions=[]\n",
+ "lineno": 592,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 591,
+ "start_region_line": 591
+ },
+ {
+ "end_outermost_loop": 596,
+ "end_region_line": 596,
+ "line": " self.collision_joints[joint_name].was_in_collision = self.collision_joints[joint_name].in_collision.copy()\n",
+ "lineno": 593,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 591,
+ "start_region_line": 591
+ },
+ {
+ "end_outermost_loop": 596,
+ "end_region_line": 596,
+ "line": " # self.collision_joints[joint_name].in_collision = {'pos': False, 'neg': False, 'min_dist_pair':None}\n",
+ "lineno": 594,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 591,
+ "start_region_line": 591
+ },
+ {
+ "end_outermost_loop": 596,
+ "end_region_line": 596,
+ "line": " self.collision_joints[joint_name].in_collision['pos'] = False\n",
+ "lineno": 595,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 591,
+ "start_region_line": 591
+ },
+ {
+ "end_outermost_loop": 596,
+ "end_region_line": 596,
+ "line": " self.collision_joints[joint_name].in_collision['neg'] = False\n",
+ "lineno": 596,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 591,
+ "start_region_line": 591
+ },
+ {
+ "end_outermost_loop": 632,
+ "end_region_line": 632,
+ "line": " # Test for collisions across all collision pairs\n",
+ "lineno": 597,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 565,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " for pair_name in self.collision_pairs:\n",
+ "lineno": 598,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " cp=self.collision_pairs[pair_name]\n",
+ "lineno": 599,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " if cp.is_valid:\n",
+ "lineno": 600,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " cp.was_in_collision=cp.in_collision\n",
+ "lineno": 601,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " if cp.detect_as=='pts':\n",
+ "lineno": 602,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " cp.in_collision=check_pts_in_AABB_cube(cube=cp.link_cube.pose,pts=cp.link_pts.pose)\n",
+ "lineno": 603,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " # cp.in_collision=check_AABB_in_AABB_from_pts(pts1=cp.link_cube.pose,pts2=cp.link_pts.pose)\n",
+ "lineno": 604,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " elif cp.detect_as=='edges':\n",
+ "lineno": 605,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " cp.in_collision = check_mesh_triangle_edges_in_cube(mesh_triangles=cp.link_pts.get_triangles(),cube=cp.link_cube.pose)\n",
+ "lineno": 606,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " else:\n",
+ "lineno": 607,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " cp.in_collision =False\n",
+ "lineno": 608,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " #cp.pretty_print()\n",
+ "lineno": 609,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": "\n",
+ "lineno": 610,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " #Propogate to links\n",
+ "lineno": 611,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " self.collision_links[cp.link_cube.name].in_collision=self.collision_links[cp.link_cube.name].in_collision or cp.in_collision\n",
+ "lineno": 612,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " self.collision_links[cp.link_pts.name].in_collision =self.collision_links[cp.link_pts.name].in_collision or cp.in_collision\n",
+ "lineno": 613,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": "\n",
+ "lineno": 614,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " # Beep on new collision\n",
+ "lineno": 615,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " if not self.collision_pairs[pair_name].was_in_collision and self.collision_pairs[pair_name].in_collision:\n",
+ "lineno": 616,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " print(f'New collision pair event: {pair_name}' )\n",
+ "lineno": 617,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 618,
+ "end_region_line": 618,
+ "line": " self.alert()\n",
+ "lineno": 618,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 598,
+ "start_region_line": 598
+ },
+ {
+ "end_outermost_loop": 619,
+ "end_region_line": 632,
+ "line": "\n",
+ "lineno": 619,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 619,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 620,
+ "end_region_line": 632,
+ "line": " normalized_joint_status_thresh = joint_cfg_thresh.value\n",
+ "lineno": 620,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 620,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 632,
+ "end_region_line": 632,
+ "line": " # print(f\"From Process: Normal CFG = {normalized_joint_status_thresh}\")\n",
+ "lineno": 621,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 565,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 632,
+ "end_region_line": 632,
+ "line": " #Now update joint state\n",
+ "lineno": 622,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 565,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 629,
+ "end_region_line": 629,
+ "line": " for joint_name in self.collision_joints:\n",
+ "lineno": 623,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 623,
+ "start_region_line": 623
+ },
+ {
+ "end_outermost_loop": 629,
+ "end_region_line": 629,
+ "line": " cj = self.collision_joints[joint_name]\n",
+ "lineno": 624,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 623,
+ "start_region_line": 623
+ },
+ {
+ "end_outermost_loop": 629,
+ "end_region_line": 629,
+ "line": " cj.update_last_joint_cfg_thresh(normalized_joint_status_thresh)\n",
+ "lineno": 625,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 623,
+ "start_region_line": 623
+ },
+ {
+ "end_outermost_loop": 629,
+ "end_region_line": 629,
+ "line": " for cp in cj.collision_pairs:\n",
+ "lineno": 626,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 623,
+ "start_region_line": 626
+ },
+ {
+ "end_outermost_loop": 629,
+ "end_region_line": 629,
+ "line": " if cp.in_collision:\n",
+ "lineno": 627,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 623,
+ "start_region_line": 626
+ },
+ {
+ "end_outermost_loop": 629,
+ "end_region_line": 629,
+ "line": " cj.active_collisions.append(cp.name) #Add collision to joint\n",
+ "lineno": 628,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 623,
+ "start_region_line": 626
+ },
+ {
+ "end_outermost_loop": 629,
+ "end_region_line": 629,
+ "line": " cj.in_collision[cj.collision_dirs[cp.name]] = True\n",
+ "lineno": 629,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 623,
+ "start_region_line": 626
+ },
+ {
+ "end_outermost_loop": 632,
+ "end_region_line": 632,
+ "line": " # print(f\"From Process: {joint_name} = {self.collision_joints[joint_name].in_collision}\")\n",
+ "lineno": 630,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 565,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 632,
+ "end_region_line": 632,
+ "line": " # self.collision_joints[joint_name].motor.step_collision_avoidance(self.collision_joints[joint_name].in_collision)\n",
+ "lineno": 631,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 565,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 632,
+ "end_region_line": 632,
+ "line": " self.prev_loop_start_ts = time.perf_counter()\n",
+ "lineno": 632,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 632,
+ "start_region_line": 565
+ },
+ {
+ "end_outermost_loop": 633,
+ "end_region_line": 651,
+ "line": " \n",
+ "lineno": 633,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 633,
+ "start_region_line": 478
+ },
+ {
+ "end_outermost_loop": 635,
+ "end_region_line": 635,
+ "line": " def alert(self):\n",
+ "lineno": 634,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 634,
+ "start_region_line": 634
+ },
+ {
+ "end_outermost_loop": 635,
+ "end_region_line": 635,
+ "line": " threading.Thread(target=chime.warning,daemon=True).start()\n",
+ "lineno": 635,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 635,
+ "start_region_line": 634
+ },
+ {
+ "end_outermost_loop": 636,
+ "end_region_line": 651,
+ "line": "\n",
+ "lineno": 636,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 636,
+ "start_region_line": 478
+ },
+ {
+ "end_outermost_loop": 643,
+ "end_region_line": 643,
+ "line": " def is_link_in_collsion(self,link_name):\n",
+ "lineno": 637,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 637,
+ "start_region_line": 637
+ },
+ {
+ "end_outermost_loop": 639,
+ "end_region_line": 643,
+ "line": " if self.urdf is None:\n",
+ "lineno": 638,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 638,
+ "start_region_line": 637
+ },
+ {
+ "end_outermost_loop": 639,
+ "end_region_line": 643,
+ "line": " return False\n",
+ "lineno": 639,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 639,
+ "start_region_line": 637
+ },
+ {
+ "end_outermost_loop": 640,
+ "end_region_line": 643,
+ "line": " try:\n",
+ "lineno": 640,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 640,
+ "start_region_line": 637
+ },
+ {
+ "end_outermost_loop": 641,
+ "end_region_line": 643,
+ "line": " return self.collision_links[link_name].in_collision\n",
+ "lineno": 641,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 641,
+ "start_region_line": 637
+ },
+ {
+ "end_outermost_loop": 642,
+ "end_region_line": 643,
+ "line": " except KeyError: #Not all links will be monitored\n",
+ "lineno": 642,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 642,
+ "start_region_line": 637
+ },
+ {
+ "end_outermost_loop": 643,
+ "end_region_line": 643,
+ "line": " return False\n",
+ "lineno": 643,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 643,
+ "start_region_line": 637
+ },
+ {
+ "end_outermost_loop": 644,
+ "end_region_line": 651,
+ "line": "\n",
+ "lineno": 644,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 644,
+ "start_region_line": 478
+ },
+ {
+ "end_outermost_loop": 651,
+ "end_region_line": 651,
+ "line": " def was_link_in_collsion(self,link_name):\n",
+ "lineno": 645,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 645,
+ "start_region_line": 645
+ },
+ {
+ "end_outermost_loop": 647,
+ "end_region_line": 651,
+ "line": " if self.urdf is None:\n",
+ "lineno": 646,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 646,
+ "start_region_line": 645
+ },
+ {
+ "end_outermost_loop": 647,
+ "end_region_line": 651,
+ "line": " return False\n",
+ "lineno": 647,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 647,
+ "start_region_line": 645
+ },
+ {
+ "end_outermost_loop": 648,
+ "end_region_line": 651,
+ "line": " try:\n",
+ "lineno": 648,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 648,
+ "start_region_line": 645
+ },
+ {
+ "end_outermost_loop": 649,
+ "end_region_line": 651,
+ "line": " return self.collision_links[link_name].was_in_collision\n",
+ "lineno": 649,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 649,
+ "start_region_line": 645
+ },
+ {
+ "end_outermost_loop": 650,
+ "end_region_line": 651,
+ "line": " except KeyError: #Not all links will be monitored\n",
+ "lineno": 650,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 650,
+ "start_region_line": 645
+ },
+ {
+ "end_outermost_loop": 651,
+ "end_region_line": 651,
+ "line": " return False\n",
+ "lineno": 651,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 651,
+ "start_region_line": 645
+ },
+ {
+ "end_outermost_loop": 652,
+ "end_region_line": 652,
+ "line": "\n",
+ "lineno": 652,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 652,
+ "start_region_line": 652
+ },
+ {
+ "end_outermost_loop": 653,
+ "end_region_line": 653,
+ "line": "\n",
+ "lineno": 653,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 653,
+ "start_region_line": 653
+ },
+ {
+ "end_outermost_loop": 676,
+ "end_region_line": 676,
+ "line": "class RobotCollision(Device):\n",
+ "lineno": 654,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 654,
+ "start_region_line": 654
+ },
+ {
+ "end_outermost_loop": 655,
+ "end_region_line": 676,
+ "line": " \"\"\"\n",
+ "lineno": 655,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 655,
+ "start_region_line": 654
+ },
+ {
+ "end_outermost_loop": 656,
+ "end_region_line": 676,
+ "line": " Deprecated. Keep shell class (for now) to avoid breaking legacy code.\n",
+ "lineno": 656,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 656,
+ "start_region_line": 654
+ },
+ {
+ "end_outermost_loop": 657,
+ "end_region_line": 676,
+ "line": " \"\"\"\n",
+ "lineno": 657,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 657,
+ "start_region_line": 654
+ },
+ {
+ "end_outermost_loop": 663,
+ "end_region_line": 663,
+ "line": " def __init__(self,robot):\n",
+ "lineno": 658,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 658,
+ "start_region_line": 658
+ },
+ {
+ "end_outermost_loop": 659,
+ "end_region_line": 663,
+ "line": " print('-----------')\n",
+ "lineno": 659,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 659,
+ "start_region_line": 658
+ },
+ {
+ "end_outermost_loop": 660,
+ "end_region_line": 663,
+ "line": " print('RobotCollision has been deprecated.')\n",
+ "lineno": 660,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 660,
+ "start_region_line": 658
+ },
+ {
+ "end_outermost_loop": 661,
+ "end_region_line": 663,
+ "line": " print('Use RobotCollisionMgmt instead')\n",
+ "lineno": 661,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 661,
+ "start_region_line": 658
+ },
+ {
+ "end_outermost_loop": 662,
+ "end_region_line": 663,
+ "line": " print('See KB post forum.hello-robot.com/xxx')\n",
+ "lineno": 662,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 662,
+ "start_region_line": 658
+ },
+ {
+ "end_outermost_loop": 663,
+ "end_region_line": 663,
+ "line": " print('-----------')\n",
+ "lineno": 663,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 663,
+ "start_region_line": 658
+ },
+ {
+ "end_outermost_loop": 664,
+ "end_region_line": 676,
+ "line": "\n",
+ "lineno": 664,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 664,
+ "start_region_line": 654
+ },
+ {
+ "end_outermost_loop": 666,
+ "end_region_line": 666,
+ "line": " def startup(self):\n",
+ "lineno": 665,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 665,
+ "start_region_line": 665
+ },
+ {
+ "end_outermost_loop": 666,
+ "end_region_line": 666,
+ "line": " pass\n",
+ "lineno": 666,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 666,
+ "start_region_line": 665
+ },
+ {
+ "end_outermost_loop": 667,
+ "end_region_line": 676,
+ "line": "\n",
+ "lineno": 667,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 667,
+ "start_region_line": 654
+ },
+ {
+ "end_outermost_loop": 669,
+ "end_region_line": 669,
+ "line": " def enable_model(self,name):\n",
+ "lineno": 668,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 668,
+ "start_region_line": 668
+ },
+ {
+ "end_outermost_loop": 669,
+ "end_region_line": 669,
+ "line": " pass\n",
+ "lineno": 669,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 669,
+ "start_region_line": 668
+ },
+ {
+ "end_outermost_loop": 670,
+ "end_region_line": 676,
+ "line": "\n",
+ "lineno": 670,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 670,
+ "start_region_line": 654
+ },
+ {
+ "end_outermost_loop": 672,
+ "end_region_line": 672,
+ "line": " def disable_model(self,name):\n",
+ "lineno": 671,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 671,
+ "start_region_line": 671
+ },
+ {
+ "end_outermost_loop": 672,
+ "end_region_line": 672,
+ "line": " pass\n",
+ "lineno": 672,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 672,
+ "start_region_line": 671
+ },
+ {
+ "end_outermost_loop": 673,
+ "end_region_line": 676,
+ "line": "\n",
+ "lineno": 673,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 673,
+ "start_region_line": 654
+ },
+ {
+ "end_outermost_loop": 674,
+ "end_region_line": 676,
+ "line": "\n",
+ "lineno": 674,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 674,
+ "start_region_line": 654
+ },
+ {
+ "end_outermost_loop": 676,
+ "end_region_line": 676,
+ "line": " def step(self):\n",
+ "lineno": 675,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 675,
+ "start_region_line": 675
+ },
+ {
+ "end_outermost_loop": 676,
+ "end_region_line": 676,
+ "line": " pass",
+ "lineno": 676,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 676,
+ "start_region_line": 675
+ }
+ ],
+ "percent_cpu_time": 0.0
+ },
+ "/home/hello-robot/repos/stretch_body/tools/bin/stretch_gamepad_teleop.py": {
+ "functions": [],
+ "imports": [
+ "from __future__ import print_function"
+ ],
+ "leaks": {},
+ "lines": [
+ {
+ "end_outermost_loop": 1,
+ "end_region_line": 1,
+ "line": "#!/usr/bin/env python3\n",
+ "lineno": 1,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 1,
+ "start_region_line": 1
+ },
+ {
+ "end_outermost_loop": 2,
+ "end_region_line": 2,
+ "line": "from __future__ import print_function\n",
+ "lineno": 2,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 2,
+ "start_region_line": 2
+ },
+ {
+ "end_outermost_loop": 3,
+ "end_region_line": 3,
+ "line": "from stretch_body.gamepad_teleop import GamePadTeleop\n",
+ "lineno": 3,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.09875386199185372,
+ "n_cpu_percent_c": 72.66747242063059,
+ "n_cpu_percent_python": 8.717201517414399,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 8.294900571721342,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 3,
+ "start_region_line": 3
+ },
+ {
+ "end_outermost_loop": 4,
+ "end_region_line": 4,
+ "line": "from stretch_body.hello_utils import print_stretch_re_use\n",
+ "lineno": 4,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 4,
+ "start_region_line": 4
+ },
+ {
+ "end_outermost_loop": 5,
+ "end_region_line": 5,
+ "line": "\n",
+ "lineno": 5,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 5,
+ "start_region_line": 5
+ },
+ {
+ "end_outermost_loop": 6,
+ "end_region_line": 6,
+ "line": "print_stretch_re_use()\n",
+ "lineno": 6,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 6,
+ "start_region_line": 6
+ },
+ {
+ "end_outermost_loop": 7,
+ "end_region_line": 7,
+ "line": "\n",
+ "lineno": 7,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 7,
+ "start_region_line": 7
+ },
+ {
+ "end_outermost_loop": 11,
+ "end_region_line": 8,
+ "line": "if __name__ == \"__main__\":\n",
+ "lineno": 8,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 8,
+ "start_region_line": 8
+ },
+ {
+ "end_outermost_loop": 9,
+ "end_region_line": 9,
+ "line": " gamepad_teleop = GamePadTeleop()\n",
+ "lineno": 9,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.04672881967450086,
+ "n_cpu_percent_c": 0.09829035717247284,
+ "n_cpu_percent_python": 0.13811137445747126,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.07978661487207629,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 9,
+ "start_region_line": 9
+ },
+ {
+ "end_outermost_loop": 10,
+ "end_region_line": 10,
+ "line": " gamepad_teleop.startup()\n",
+ "lineno": 10,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.04220983946906068,
+ "n_cpu_percent_c": 3.01378266188074,
+ "n_cpu_percent_python": 3.742653239676631,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 1,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 3.2478012421744835,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 10,
+ "start_region_line": 10
+ },
+ {
+ "end_outermost_loop": 11,
+ "end_region_line": 11,
+ "line": " gamepad_teleop.mainloop()\n",
+ "lineno": 11,
+ "memory_samples": [],
+ "n_avg_mb": 0.0,
+ "n_copy_mb_s": 0.0,
+ "n_core_utilization": 0.0,
+ "n_cpu_percent_c": 0.0,
+ "n_cpu_percent_python": 0.0,
+ "n_gpu_avg_memory_mb": 0.0,
+ "n_gpu_peak_memory_mb": 0.0,
+ "n_gpu_percent": 0,
+ "n_growth_mb": 0.0,
+ "n_malloc_mb": 0.0,
+ "n_mallocs": 0,
+ "n_peak_mb": 0.0,
+ "n_python_fraction": 0,
+ "n_sys_percent": 0.0,
+ "n_usage_fraction": 0.0,
+ "start_outermost_loop": 11,
+ "start_region_line": 11
+ }
+ ],
+ "percent_cpu_time": 99.99999999999999
+ }
+ },
+ "gpu": false,
+ "growth_rate": 101.13007515194356,
+ "max_footprint_fname": "/home/hello-robot/repos/stretch_body/body/stretch_body/dynamixel_XL430.py",
+ "max_footprint_lineno": 447,
+ "max_footprint_mb": 50.60268783569336,
+ "max_footprint_python_fraction": 0.999702,
+ "memory": true,
+ "program": "/home/hello-robot/repos/stretch_body/tools/bin/stretch_gamepad_teleop.py",
+ "samples": [
+ [
+ 657344651,
+ 10.034314155578613
+ ],
+ [
+ 657349281,
+ 10.128557205200195
+ ],
+ [
+ 657350014,
+ 10.222800254821777
+ ],
+ [
+ 889609813,
+ 20.2229585647583
+ ],
+ [
+ 889611725,
+ 20.317201614379883
+ ],
+ [
+ 1035168358,
+ 30.317264556884766
+ ],
+ [
+ 1035171003,
+ 30.411507606506348
+ ],
+ [
+ 1238979099,
+ 40.41176986694336
+ ],
+ [
+ 1238981666,
+ 40.50601291656494
+ ],
+ [
+ 1779370335,
+ 50.50844478607178
+ ],
+ [
+ 1779372799,
+ 50.60268783569336
+ ]
+ ],
+ "stacks": []
+}