diff --git a/.catkin_tools/profiles/default/devel_collisions.txt b/.catkin_tools/profiles/default/devel_collisions.txt index 641c8c6c7f74edba53652dc4a810dc9769a53211..2887213cc991ef8f5e56bc786443b3740ee825cd 100644 --- a/.catkin_tools/profiles/default/devel_collisions.txt +++ b/.catkin_tools/profiles/default/devel_collisions.txt @@ -1,4 +1,4 @@ /home/matteo/ws_panda/devel/./cmake.lock 42 -/home/matteo/reachability/devel/./cmake.lock 16019 +/home/matteo/reachability/devel/./cmake.lock 17431 /home/matteo/reachability/devel/lib/libmoveit_grasps.so 79 /home/matteo/reachability/devel/lib/libmoveit_grasps_filter.so 79 diff --git a/src/ceti_double/launch/demo.launch b/src/ceti_double/launch/demo.launch index 2d39189fc077d136421592a4cf6e47472fae2979..30e85064d6a46ac3d3a25077f1c4fdde32e7c1df 100644 --- a/src/ceti_double/launch/demo.launch +++ b/src/ceti_double/launch/demo.launch @@ -24,8 +24,8 @@ <arg name="use_rviz" default="true" /> <!-- If needed, broadcast static tf for robot root --> - <node pkg="tf2_ros" type="static_transform_publisher" name="virtual_joint_broadcaster_0" args="0 0 0 0 0 0 world base1" /> - <node pkg="tf2_ros" type="static_transform_publisher" name="virtual_joint_broadcaster_1" args="0 0 0 0 0 0 world base2" /> + <node pkg="tf2_ros" type="static_transform_publisher" name="virtual_joint_broadcaster_0" args="0 0 0 0 0 0 world base_1" /> + <node pkg="tf2_ros" type="static_transform_publisher" name="virtual_joint_broadcaster_1" args="0 0 0 0 0 0 world base_2" /> diff --git a/src/franka_description/robots/ceti_double.urdf.xacro b/src/franka_description/robots/ceti_double.urdf.xacro index 4a54ab2bbff093e919d46336b655af4f2e6acc92..82c3dec04bcd299d594bc2d08cb5cfc24b03859a 100644 --- a/src/franka_description/robots/ceti_double.urdf.xacro +++ b/src/franka_description/robots/ceti_double.urdf.xacro @@ -11,7 +11,7 @@ <link name="world" /> - <xacro:property name="yaml_file" value="$(find mtc)/results/298901127.yaml" /> + <xacro:property name="yaml_file" value="$(find mtc)/results/dummy.yaml" /> <xacro:property name="props" value="${xacro.load_yaml(yaml_file)}" /> <xacro:property name="x1" value="${props['objects'][8]['pos']['x']}" /> diff --git a/src/mtc/include/impl/abstract_mediator.h b/src/mtc/include/impl/abstract_mediator.h index 7bee017cb617eadee9cd99c235a589ff13bac335..6417f3a0cc9f0a841926c83d4d5dd0a8477da7d2 100644 --- a/src/mtc/include/impl/abstract_mediator.h +++ b/src/mtc/include/impl/abstract_mediator.h @@ -41,11 +41,12 @@ class Abstract_mediator { public: Abstract_mediator(std::vector<std::vector<tf2::Transform>> objects, ros::Publisher* pub) : objects_(objects), pub_(pub){ - /* - wings_.push_back(wing_BP("right_panel", tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(0,0.6525f,0.4425f -0.005f)), right_size)); - wings_.push_back(wing_BP("front_panel", tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(0.6525f,0,0.4425f-0.005f)), mid_size)); - wings_.push_back(wing_BP("left_panel", tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(0,-0.6525f,0.4425f -0.005f)), left_size)); - */ + std::vector<wing_BP> wings; + wings.push_back({"right_panel", tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(0,0.6525f,0.4425f -0.005f)), right_size}); + wings.push_back({"right_panel", tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(0,0.6525f,0.4425f -0.005f)), right_size}); + wings.push_back({"right_panel", tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(0,0.6525f,0.4425f -0.005f)), right_size}); + wings_.push_back(wings); + wings_.push_back(wings); } inline void connect_robots(Abstract_robot* robot) {robots_.push_back(robot); ROS_INFO("%s connected...", robot->name().c_str());} diff --git a/src/mtc/include/impl/abstract_robot.h b/src/mtc/include/impl/abstract_robot.h index 69928e0325bc0538e3aea2804af2fb47c23b9c7b..50be7a180a9cbf5e3289da4c6e213271e59efa6b 100644 --- a/src/mtc/include/impl/abstract_robot.h +++ b/src/mtc/include/impl/abstract_robot.h @@ -68,7 +68,7 @@ class Abstract_robot { virtual void notify()= 0; - virtual bool check_single_object_collision(tf2::Transform& obj)= 0; + virtual bool check_single_object_collision(tf2::Transform& obj, std::string& b)= 0; virtual void workload_checker(std::vector<int>& count_vector, tf2::Transform& obj) =0; }; diff --git a/src/mtc/include/impl/mediator.h b/src/mtc/include/impl/mediator.h index 74a2da1e362693c38e929c96e1574a4dee0b1b3f..7573cc3879d12f91811ea700dc96d50fb8cb9f9b 100644 --- a/src/mtc/include/impl/mediator.h +++ b/src/mtc/include/impl/mediator.h @@ -18,7 +18,7 @@ class Mediator : public Abstract_mediator{ pcl::PointCloud< pcl::PointXYZ >::Ptr vector_to_cloud(std::vector<pcl::PointXYZ>& vector); std::vector<pcl::PointXYZ> generate_Ground(const tf2::Vector3 origin, const float diameter, float resolution); - void approximation(Robot* robot, int& wings); + void approximation(Robot* robot); void write_file(Robot* A, Robot* B); diff --git a/src/mtc/include/impl/moveit_mediator.h b/src/mtc/include/impl/moveit_mediator.h index 77c2c499450f815e7e05a651a4b3908582751cfc..e1edb2300e824b7c822ed47d45de4ed080d15fee 100644 --- a/src/mtc/include/impl/moveit_mediator.h +++ b/src/mtc/include/impl/moveit_mediator.h @@ -34,10 +34,9 @@ class Moveit_mediator : public Abstract_mediator{ void mediate() override; void build_wings(std::bitset<3>& wing,int& robot) override; - void publish_tables(); + void publish_tables(moveit::planning_interface::PlanningSceneInterface& psi); void load_robot_description(); - void rewrite_task_template(); - + void rewrite_task_template(Abstract_robot* r, moveit_msgs::CollisionObject& target); }; #endif \ No newline at end of file diff --git a/src/mtc/include/impl/robot.h b/src/mtc/include/impl/robot.h index 6a0a891e1806838977f4872cacf6be29c5c27eb6..95b69339920f50f53ef398a464a4cbea52c50b16 100644 --- a/src/mtc/include/impl/robot.h +++ b/src/mtc/include/impl/robot.h @@ -43,7 +43,7 @@ class Robot : public Abstract_robot{ float area_calculation(tf2::Transform& A, tf2::Transform& B, tf2::Transform& C); bool check_robot_collision(Robot* R); - bool check_single_object_collision(tf2::Transform& obj) override; + bool check_single_object_collision(tf2::Transform& obj, std::string& str) override; void workload_checker(std::vector<int>& count_vector, tf2::Transform& obj) override; void notify() override; diff --git a/src/mtc/include/impl/wing.h b/src/mtc/include/impl/wing.h index f94a8040bfa6dad9bfd29e943464fd42da24635a..9a920c21776a74a1e5de5beb38b0611b75e07c63 100644 --- a/src/mtc/include/impl/wing.h +++ b/src/mtc/include/impl/wing.h @@ -20,6 +20,7 @@ class Wing : public Abstract_robot_element{ } inline std::string& name() {return name_;} + inline void set_name(std::string& str) {name_ = str;} inline tf2::Vector3 size(){ return size_;} inline std::vector<tf2::Transform>& bounds() {return bounds_;} void update(tf2::Transform& tf) override {this->calc_world_tf(tf);} diff --git a/src/mtc/launch/cell_routine.launch b/src/mtc/launch/cell_routine.launch index 80eff90b47f04faf82758e88e05c1931329258a9..bc0e5c3dcf5f874a1412c580514a742ae85073e9 100644 --- a/src/mtc/launch/cell_routine.launch +++ b/src/mtc/launch/cell_routine.launch @@ -1,18 +1,23 @@ <launch> <!--<include file="$(find panda_moveit_config)/launch/demo.launch"></include> --> - <rosparam command="load" file="$(find mtc)/results/298901127.yaml"/> + <rosparam command="load" file="$(find mtc)/results/dummy.yaml"/> <rosparam command="load" file="$(find mtc)/mtc_task_file/dummy.yaml" /> <rosparam command="load" file="$(find mtc)/maps/dummy.yaml"/> <rosparam command="load" file="$(find mtc)/descriptions/dummy.yaml"/> + <include file="$(find ceti_double)/launch/demo.launch"> + <arg name="use_rviz" value="false"/> </include> + <param name="move_group/capabilities" value="move_group/ExecuteTaskSolutionCapability" /> + <include file="$(find ceti_double)/launch/moveit_rviz.launch"> <arg name="rviz_config" value="$(find mtc)/launch/rviz/cell_routine.rviz" /> </include> - <node pkg="mtc" type="cell_routine" name="cell_routine" output="screen" required="true" /> + <node pkg="mtc" type="cell_routine" name="cell_routine" output="screen" required="true"> + </node> </launch> diff --git a/src/mtc/mtc_task_file/dummy.yaml b/src/mtc/mtc_task_file/dummy.yaml index 44f7293c41c824f89aa79f2bad719f2b4e752210..7c8ceb37494b3f474704b8b1f375f34a3f8d2acf 100644 --- a/src/mtc/mtc_task_file/dummy.yaml +++ b/src/mtc/mtc_task_file/dummy.yaml @@ -80,7 +80,7 @@ task: propertiesConfigureInitFrom: source: PARENT properties: - object: bottle + object: "" angle_delta: 1.571 pregrasp: open set: @@ -88,7 +88,7 @@ task: - type: ModifyPlanningScene set: allow_collisions: - first: bottle + first: "" second: joint_model_group_name: "" allow: true @@ -103,6 +103,12 @@ task: attach_object: object: "" link: "" + - type: ModifyPlanningScene + set: + allow_collisions: + first: "" + second: "" + allow: true - type: MoveRelative planner: cartesian id: pick_up @@ -117,6 +123,12 @@ task: link: "" direction: vector: {x: 0.0, y: 0.0, z: 1.0} + - type: ModifyPlanningScene + set: + allow_collisions: + first: "" + second: "" + allow: false - type: Connect group_planner_vector: panda_arm1: sampling @@ -130,6 +142,12 @@ task: propertiesConfigureInitFrom: source: PARENT stages: + - type: ModifyPlanningScene + set: + allow_collisions: + first: "" + second: "" + allow: true - type: MoveRelative planner: cartesian properties: @@ -160,7 +178,7 @@ task: set: monitored_stage: pick_up pose: - point: {x: 0.100000, y: 0.300000, z: 0.9305} + point: {x: 0, y: 0, z: 0} orientation: {x: 0.0, y: 0.0, z: 0.0, w: 1.0} - type: MoveTo planner: sampling @@ -174,7 +192,7 @@ task: object: "" link: "" allow_collisions: - first: bottle + first: "" second: joint_model_group_name: "" allow: false @@ -205,4 +223,4 @@ task: - group set: goal: ready -max_planning_solutions: 10 \ No newline at end of file +max_planning_solutions: 10 diff --git a/src/mtc/results/-1785667697.yaml b/src/mtc/results/-1785667697.yaml deleted file mode 100644 index aa03b2cbd28b315784c736e1c317ef7db82733c8..0000000000000000000000000000000000000000 --- a/src/mtc/results/-1785667697.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.000002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.043621 , 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.087269 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.113744, 'y': 1.300032, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.737278 , 'w': 0.675589 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.658065}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.056873 , 'y': 0.650015 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.043621 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': 0.056869 , 'y': -0.650019 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.043621 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.170614, 'y': 1.950049 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.737278, 'w': 0.675589 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_left_panel', 'pos': { 'x': 0.536273, 'y': 1.356902 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.737278, 'w': 0.675589 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.219165, 'y': -0.019177, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.043621, 'w': 0.999048 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.094569, 'y': 1.080869, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.737278, 'w': 0.675589 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/-1821002738.yaml b/src/mtc/results/-1821002738.yaml deleted file mode 100644 index 2c52e6e393b550836bbbf68ae8db3b1561d7366f..0000000000000000000000000000000000000000 --- a/src/mtc/results/-1821002738.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.000002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.043621 , 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.087269 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.113744, 'y': 1.300032, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.043621 , 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.087269}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.056873 , 'y': 0.650015 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.043621 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': 0.056869 , 'y': -0.650019 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.043621 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.170614, 'y': 1.950049 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.043621, 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': 0.536273, 'y': 1.356903 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.043621, 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.219165, 'y': -0.019177, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.043621, 'w': 0.999048 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.332906, 'y': 1.280857, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.043621, 'w': 0.999048 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/-1934684646.yaml b/src/mtc/results/-1934684646.yaml deleted file mode 100644 index dae7425a77af3fa327ee98e5fdd1c2b11134ec63..0000000000000000000000000000000000000000 --- a/src/mtc/results/-1934684646.yaml +++ /dev/null @@ -1,25 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.000002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.000005, 'y': 1.304998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.000003}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.000004 , 'y': 0.652498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.000000 , 'y': -0.652502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.000007, 'y': 1.957498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.220002, 'y': -0.000003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.220005, 'y': 1.304997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/-2005299998.yaml b/src/mtc/results/-2005299998.yaml deleted file mode 100644 index 80702e2372207528143d8434739ac5c56364304e..0000000000000000000000000000000000000000 --- a/src/mtc/results/-2005299998.yaml +++ /dev/null @@ -1,27 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': 0.099998 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.404998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.707108 , 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.570799}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.752498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.552498 , 'y': 0.100000 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.552502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.100007, 'y': 2.057498 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_left_panel', 'pos': { 'x': 0.552495, 'y': 1.405000 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': 0.099997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.100005, 'y': 1.184998, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/-2042372792.yaml b/src/mtc/results/-2042372792.yaml deleted file mode 100644 index 53c319653756e55a8e055313e8190abfd494d213..0000000000000000000000000000000000000000 --- a/src/mtc/results/-2042372792.yaml +++ /dev/null @@ -1,27 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': 0.099998 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.404998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.000003}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.752498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.552498 , 'y': 0.100000 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.552502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.100007, 'y': 2.057498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': 0.552495, 'y': 1.405000 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': 0.099997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.320005, 'y': 1.404997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/-2054540989.yaml b/src/mtc/results/-2054540989.yaml deleted file mode 100644 index f3d814b0b1a7efe15e8a7c5a765a59c80c781210..0000000000000000000000000000000000000000 --- a/src/mtc/results/-2054540989.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': 0.099998 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.404998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.707108 , 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.570799}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.752498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.552498 , 'y': 0.100000 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.552502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.100007, 'y': 2.057498 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': 0.099997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.100005, 'y': 1.184998, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/-2065119826.yaml b/src/mtc/results/-2065119826.yaml deleted file mode 100644 index 744891a933997d56772e3b8aa0271bcd3e58a00c..0000000000000000000000000000000000000000 --- a/src/mtc/results/-2065119826.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': 0.099998 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.404998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.000003}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.752498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.552498 , 'y': 0.100000 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.552502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.100007, 'y': 2.057498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': 0.099997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.320005, 'y': 1.404997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/-2070036432.yaml b/src/mtc/results/-2070036432.yaml deleted file mode 100644 index 462222978aeb2ad04f0ac9b28c9ee216e90e859f..0000000000000000000000000000000000000000 --- a/src/mtc/results/-2070036432.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.000002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.043619 , 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.087266 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.113740, 'y': 1.300032, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.737277 , 'w': 0.675590 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.658063}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.056871 , 'y': 0.650015 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.043619 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': 0.056867 , 'y': -0.650019 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.043619 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.170610, 'y': 1.950049 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.737277, 'w': 0.675590 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_left_panel', 'pos': { 'x': 0.536277, 'y': 1.356901 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.737277, 'w': 0.675590 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.219165, 'y': -0.019176, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.043619, 'w': 0.999048 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.094566, 'y': 1.080869, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.737277, 'w': 0.675590 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/-2105624039.yaml b/src/mtc/results/-2105624039.yaml deleted file mode 100644 index 7e50483aac9d2f3a72996075f2b1e00101be90e4..0000000000000000000000000000000000000000 --- a/src/mtc/results/-2105624039.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.000002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.043619 , 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.087266 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.113740, 'y': 1.300032, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.043619 , 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.087267}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.056871 , 'y': 0.650015 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.043619 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': 0.056867 , 'y': -0.650019 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.043619 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.170610, 'y': 1.950049 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.043619, 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': 0.536277, 'y': 1.356901 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.043619, 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.219165, 'y': -0.019176, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.043619, 'w': 0.999048 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.332903, 'y': 1.280858, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.043619, 'w': 0.999048 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1009749163.yaml b/src/mtc/results/1009749163.yaml deleted file mode 100644 index 7a010f2585591b0ab64d7c8c9e4e7fa72a6d8af3..0000000000000000000000000000000000000000 --- a/src/mtc/results/1009749163.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': -0.100002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.204998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.707108 , 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.570799}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.552498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.752502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.100007, 'y': 1.857498 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_left_panel', 'pos': { 'x': 0.552495, 'y': 1.205000 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': -0.100003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.100005, 'y': 0.984998, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1055349651.yaml b/src/mtc/results/1055349651.yaml deleted file mode 100644 index e42bee95e29baf2374ca1b405ab8954037fef789..0000000000000000000000000000000000000000 --- a/src/mtc/results/1055349651.yaml +++ /dev/null @@ -1,25 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.304998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.000003}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.652498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.652502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.100007, 'y': 1.957498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': -0.000003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.320005, 'y': 1.304997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1066094314.yaml b/src/mtc/results/1066094314.yaml deleted file mode 100644 index 15d0c82dcdce4b95ab663a52108fbcddbd298a92..0000000000000000000000000000000000000000 --- a/src/mtc/results/1066094314.yaml +++ /dev/null @@ -1,25 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.304998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.707108 , 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.570799}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.652498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.652502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.100007, 'y': 1.957498 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': -0.000003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.100005, 'y': 1.084998, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1078753196.yaml b/src/mtc/results/1078753196.yaml deleted file mode 100644 index ae21ee8ff4bbed2ac059d365bcf4c731516ed1be..0000000000000000000000000000000000000000 --- a/src/mtc/results/1078753196.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.304998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.000003}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.652498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.652502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.100007, 'y': 1.957498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': 0.552495, 'y': 1.305000 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': -0.000003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.320005, 'y': 1.304997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1114475889.yaml b/src/mtc/results/1114475889.yaml deleted file mode 100644 index 8d3395fb52340ce93852f3a82794fa0f130eddc9..0000000000000000000000000000000000000000 --- a/src/mtc/results/1114475889.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.304998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.707108 , 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.570799}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.652498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.652502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.100007, 'y': 1.957498 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_left_panel', 'pos': { 'x': 0.552495, 'y': 1.305000 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': -0.000003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.100005, 'y': 1.084998, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1121318535.yaml b/src/mtc/results/1121318535.yaml deleted file mode 100644 index 973c0c0088d974d35126a04e0e0b9ce44914bd04..0000000000000000000000000000000000000000 --- a/src/mtc/results/1121318535.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': -0.100002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.204998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.000003}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.552498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.552498 , 'y': -0.100000 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.752502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.100007, 'y': 1.857498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': -0.100003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.320005, 'y': 1.204997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1132193382.yaml b/src/mtc/results/1132193382.yaml deleted file mode 100644 index 4c0725ca0f62c609af3db0252610ff283d37d64d..0000000000000000000000000000000000000000 --- a/src/mtc/results/1132193382.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': -0.100002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.204998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.707108 , 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.570799}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.552498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.552498 , 'y': -0.100000 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.752502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.100007, 'y': 1.857498 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': -0.100003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.100005, 'y': 0.984998, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1144412079.yaml b/src/mtc/results/1144412079.yaml deleted file mode 100644 index 87bc071f7baba903117f6423492e0acb177bf779..0000000000000000000000000000000000000000 --- a/src/mtc/results/1144412079.yaml +++ /dev/null @@ -1,27 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': -0.100002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.204998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.000003}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.552498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.552498 , 'y': -0.100000 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.752502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.100007, 'y': 1.857498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': 0.552495, 'y': 1.205000 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': -0.100003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.320005, 'y': 1.204997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/114528184.yaml b/src/mtc/results/114528184.yaml deleted file mode 100644 index 5988be57533e62e501a15a019c2afd27a327a328..0000000000000000000000000000000000000000 --- a/src/mtc/results/114528184.yaml +++ /dev/null @@ -1,27 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.200002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.200005, 'y': 1.304998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.000003}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.200004 , 'y': 0.652498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.452498 , 'y': -0.000000 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.200000 , 'y': -0.652502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.200007, 'y': 1.957498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': 0.452495, 'y': 1.305000 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.420002, 'y': -0.000003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.420005, 'y': 1.304997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1160060243.yaml b/src/mtc/results/1160060243.yaml deleted file mode 100644 index f04949c2a588e684ec3dcdfafa67ea410fa20868..0000000000000000000000000000000000000000 --- a/src/mtc/results/1160060243.yaml +++ /dev/null @@ -1,25 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': 0.099998 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.404998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.000003}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.752498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.552502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.100007, 'y': 2.057498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': 0.099997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.320005, 'y': 1.404997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1170927557.yaml b/src/mtc/results/1170927557.yaml deleted file mode 100644 index 2b91f347c4dba9276e9f69262cf7a0a29b3e7687..0000000000000000000000000000000000000000 --- a/src/mtc/results/1170927557.yaml +++ /dev/null @@ -1,25 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': 0.099998 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.404998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.707108 , 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.570799}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.752498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.552502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.100007, 'y': 2.057498 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': 0.099997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.100005, 'y': 1.184998, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1176800679.yaml b/src/mtc/results/1176800679.yaml deleted file mode 100644 index c9b3239d2ef4e2cd87bec6b6a3c2a14516bca68f..0000000000000000000000000000000000000000 --- a/src/mtc/results/1176800679.yaml +++ /dev/null @@ -1,27 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': -0.100002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.204998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.707108 , 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.570799}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.552498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.552498 , 'y': -0.100000 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.752502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.100007, 'y': 1.857498 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_left_panel', 'pos': { 'x': 0.552495, 'y': 1.205000 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': -0.100003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.100005, 'y': 0.984998, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1183463579.yaml b/src/mtc/results/1183463579.yaml deleted file mode 100644 index 9bc946f48dd4c1739c6808c90fa37edad0a4904f..0000000000000000000000000000000000000000 --- a/src/mtc/results/1183463579.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': 0.099998 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.404998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.000003}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.752498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.552502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.100007, 'y': 2.057498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': 0.552495, 'y': 1.405000 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': 0.099997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.320005, 'y': 1.404997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1218779973.yaml b/src/mtc/results/1218779973.yaml deleted file mode 100644 index 3b75c9dda68751ecd96726caed464ca3ec27859e..0000000000000000000000000000000000000000 --- a/src/mtc/results/1218779973.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': 0.099998 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.404998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.707108 , 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.570799}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.752498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.552502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.100007, 'y': 2.057498 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_left_panel', 'pos': { 'x': 0.552495, 'y': 1.405000 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': 0.099997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.100005, 'y': 1.184998, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/148591919.yaml b/src/mtc/results/148591919.yaml deleted file mode 100644 index 1481514614be5da456614aac88907ed2f28f585d..0000000000000000000000000000000000000000 --- a/src/mtc/results/148591919.yaml +++ /dev/null @@ -1,27 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.200002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.200005, 'y': 1.304998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.707108 , 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.570799}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.200004 , 'y': 0.652498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.452498 , 'y': -0.000000 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.200000 , 'y': -0.652502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.200007, 'y': 1.957498 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_left_panel', 'pos': { 'x': 0.452495, 'y': 1.305000 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.420002, 'y': -0.000003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.200005, 'y': 1.084998, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1664651135.yaml b/src/mtc/results/1664651135.yaml deleted file mode 100644 index 43da2d702df6f9ca9360771d7dfa3d237cb67d06..0000000000000000000000000000000000000000 --- a/src/mtc/results/1664651135.yaml +++ /dev/null @@ -1,25 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.000002 , 'y': -0.200002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.000006, 'y': 1.399998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.000003}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.000004 , 'y': 0.452498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.000000 , 'y': -0.852502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.000008, 'y': 2.052498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.220002, 'y': -0.200003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.220006, 'y': 1.399997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1675054456.yaml b/src/mtc/results/1675054456.yaml deleted file mode 100644 index fbfa22719991b0b60a1c1cbe086d00bbf45eac73..0000000000000000000000000000000000000000 --- a/src/mtc/results/1675054456.yaml +++ /dev/null @@ -1,25 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.000002 , 'y': -0.200002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.000005, 'y': 1.104998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.000003}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.000004 , 'y': 0.452498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.000000 , 'y': -0.852502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.000007, 'y': 1.757498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.220002, 'y': -0.200003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.220005, 'y': 1.104997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1681835555.yaml b/src/mtc/results/1681835555.yaml deleted file mode 100644 index 016895b6c06d52c9967fd17610f98455ddcd3b79..0000000000000000000000000000000000000000 --- a/src/mtc/results/1681835555.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.304998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.000003}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.652498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.552498 , 'y': -0.000000 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.652502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.100007, 'y': 1.957498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': -0.000003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.320005, 'y': 1.304997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1692277982.yaml b/src/mtc/results/1692277982.yaml deleted file mode 100644 index 9a9d5d7b4600064f6504c1f7988643a52fb49661..0000000000000000000000000000000000000000 --- a/src/mtc/results/1692277982.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.304998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.707108 , 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.570799}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.652498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.552498 , 'y': -0.000000 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.652502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.100007, 'y': 1.957498 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': -0.000003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.100005, 'y': 1.084998, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1704405179.yaml b/src/mtc/results/1704405179.yaml deleted file mode 100644 index 8fef93f59a046c4f799fc082e5fc53b25cd8f426..0000000000000000000000000000000000000000 --- a/src/mtc/results/1704405179.yaml +++ /dev/null @@ -1,27 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.304998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.000003}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.652498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.552498 , 'y': -0.000000 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.652502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.100007, 'y': 1.957498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': 0.552495, 'y': 1.305000 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': -0.000003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.320005, 'y': 1.304997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1737201961.yaml b/src/mtc/results/1737201961.yaml deleted file mode 100644 index 0940e37d72580af86474e2bf7a9dcd7cb1a64ddf..0000000000000000000000000000000000000000 --- a/src/mtc/results/1737201961.yaml +++ /dev/null @@ -1,27 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.304998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.707108 , 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.570799}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.652498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.552498 , 'y': -0.000000 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.652502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.100007, 'y': 1.957498 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_left_panel', 'pos': { 'x': 0.552495, 'y': 1.305000 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': -0.000003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.100005, 'y': 1.084998, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/18966477.yaml b/src/mtc/results/18966477.yaml deleted file mode 100644 index b337883158457a39db738dbbbbc6c7dc39c9c79e..0000000000000000000000000000000000000000 --- a/src/mtc/results/18966477.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.200002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': 0.000000 , 'y': -0.087264 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.086267, 'y': 1.300032, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.675591 , 'w': 0.737276 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.483532}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.143135 , 'y': 0.650015 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.450015 , 'y': -0.056870 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.256870 , 'y': -0.650019 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.029400, 'y': 1.950049 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.675591, 'w': 0.737276 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.419165, 'y': 0.019172, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': -0.043618, 'w': 0.999048 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.105441, 'y': 1.080869, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.675591, 'w': 0.737276 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/1985071259.yaml b/src/mtc/results/1985071259.yaml deleted file mode 100644 index 9708aa321171c0a8f7ccf858c119ca08ec9fba27..0000000000000000000000000000000000000000 --- a/src/mtc/results/1985071259.yaml +++ /dev/null @@ -1,25 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.000002 , 'y': -0.100002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.000005, 'y': 1.204998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.000003}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.000004 , 'y': 0.552498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.000000 , 'y': -0.752502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.000007, 'y': 1.857498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.220002, 'y': -0.100003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.220005, 'y': 1.204997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/2145537375.yaml b/src/mtc/results/2145537375.yaml deleted file mode 100644 index e9fa0d03d3a4f570d7eae23c8ea33a50ca1a514a..0000000000000000000000000000000000000000 --- a/src/mtc/results/2145537375.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': 0.099998 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': 0.000000 , 'y': -0.087264 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': 0.013733, 'y': 1.400032, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': 0.000000, 'y': -0.087264}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.043135 , 'y': 0.750015 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.550015 , 'y': 0.043130 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.156870 , 'y': -0.550019 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': 0.070600, 'y': 2.050050 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': -0.043618, 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.319165, 'y': 0.119172, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': -0.043618, 'w': 0.999048 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.205430, 'y': 1.419206, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': -0.043618, 'w': 0.999048 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/298901127.yaml b/src/mtc/results/298901127.yaml deleted file mode 100644 index 5ae59799953ad7c51d1950cd43e81db431f6589c..0000000000000000000000000000000000000000 --- a/src/mtc/results/298901127.yaml +++ /dev/null @@ -1,27 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.200002 , 'y': 0.099998 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': 0.000000 , 'y': -0.087264 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.086267, 'y': 1.400032, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': 0.000000, 'y': -0.087264}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.143135 , 'y': 0.750015 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.450015 , 'y': 0.043130 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.256870 , 'y': -0.550019 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.029400, 'y': 2.050050 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': -0.043618, 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': 0.563750, 'y': 1.343165 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': -0.043618, 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.419165, 'y': 0.119172, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': -0.043618, 'w': 0.999048 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.305430, 'y': 1.419206, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': -0.043618, 'w': 0.999048 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/30759948.yaml b/src/mtc/results/30759948.yaml deleted file mode 100644 index 18d5b94e606ee13f6d5ce1cfc5fdd3f8c2ed0306..0000000000000000000000000000000000000000 --- a/src/mtc/results/30759948.yaml +++ /dev/null @@ -1,27 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.200002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': 0.000000 , 'y': -0.087264 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.086267, 'y': 1.300032, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': 0.000000, 'y': -0.087264}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.143135 , 'y': 0.650015 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.450015 , 'y': -0.056870 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.256870 , 'y': -0.650019 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.029400, 'y': 1.950049 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': -0.043618, 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': 0.563750, 'y': 1.243165 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': -0.043618, 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.419165, 'y': 0.019172, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': -0.043618, 'w': 0.999048 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.305430, 'y': 1.319206, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': -0.043618, 'w': 0.999048 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/331487535.yaml b/src/mtc/results/331487535.yaml deleted file mode 100644 index 516201ca91a77cc481fea2ca9e92840d2f77b1f8..0000000000000000000000000000000000000000 --- a/src/mtc/results/331487535.yaml +++ /dev/null @@ -1,27 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.200002 , 'y': 0.099998 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': 0.000000 , 'y': -0.087264 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.086267, 'y': 1.400032, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.675591 , 'w': 0.737276 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.483532}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.143135 , 'y': 0.750015 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.450015 , 'y': 0.043130 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.256870 , 'y': -0.550019 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.029400, 'y': 2.050050 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.675591, 'w': 0.737276 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_left_panel', 'pos': { 'x': 0.563750, 'y': 1.343165 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.675591, 'w': 0.737276 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.419165, 'y': 0.119172, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': -0.043618, 'w': 0.999048 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.105441, 'y': 1.180869, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.675591, 'w': 0.737276 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/63055095.yaml b/src/mtc/results/63055095.yaml deleted file mode 100644 index ef6da50c973b6c6de03521ad17296a703c37116b..0000000000000000000000000000000000000000 --- a/src/mtc/results/63055095.yaml +++ /dev/null @@ -1,27 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.200002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': 0.000000 , 'y': -0.087264 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.086267, 'y': 1.300032, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.675591 , 'w': 0.737276 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.483532}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.143135 , 'y': 0.650015 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.450015 , 'y': -0.056870 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.256870 , 'y': -0.650019 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.029400, 'y': 1.950049 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.675591, 'w': 0.737276 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_left_panel', 'pos': { 'x': 0.563750, 'y': 1.243165 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.675591, 'w': 0.737276 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.419165, 'y': 0.019172, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': -0.043618, 'w': 0.999048 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.105441, 'y': 1.080869, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.675591, 'w': 0.737276 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/8759084.yaml b/src/mtc/results/8759084.yaml deleted file mode 100644 index 70b5f723ebe215385cccb608b4a98af85b4f710f..0000000000000000000000000000000000000000 --- a/src/mtc/results/8759084.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.200002 , 'y': -0.000002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': 0.000000 , 'y': -0.087264 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.086267, 'y': 1.300032, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': 0.000000, 'y': -0.087264}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.143135 , 'y': 0.650015 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_front_panel' , 'pos': { 'x': 0.450015 , 'y': -0.056870 , 'z': 0.880000 } , 'size': { 'length': 0.500000 , 'width': 0.700000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.256870 , 'y': -0.650019 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': -0.043618 , 'w': 0.999048 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.029400, 'y': 1.950049 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': -0.043618, 'w': 0.999048 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.419165, 'y': 0.019172, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': -0.043618, 'w': 0.999048 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.305430, 'y': 1.319206, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': -0.043618, 'w': 0.999048 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/950455502.yaml b/src/mtc/results/950455502.yaml deleted file mode 100644 index 01213a15c9d160023111dd3f2fdda7f0d6616ecd..0000000000000000000000000000000000000000 --- a/src/mtc/results/950455502.yaml +++ /dev/null @@ -1,25 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': -0.100002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.204998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.000003}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.552498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.752502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.100007, 'y': 1.857498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': -0.100003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.320005, 'y': 1.204997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/961502182.yaml b/src/mtc/results/961502182.yaml deleted file mode 100644 index ef5c969b8c7d22afdbc9c0a4ef9cf56da87e6d4a..0000000000000000000000000000000000000000 --- a/src/mtc/results/961502182.yaml +++ /dev/null @@ -1,25 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': -0.100002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.204998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.707108 , 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 1.570799}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.552498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.752502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': -0.100007, 'y': 1.857498 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': -0.100003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.100005, 'y': 0.984998, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.707108, 'w': 0.707106 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/974324017.yaml b/src/mtc/results/974324017.yaml deleted file mode 100644 index 7fe8a2620b8fa12902dd74629624fe706273b4cc..0000000000000000000000000000000000000000 --- a/src/mtc/results/974324017.yaml +++ /dev/null @@ -1,26 +0,0 @@ -{ 'objects' : [ -{ 'id' : 'table1_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table1_table_top', 'pos': { 'x': -0.100002 , 'y': -0.100002 , 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000 , 'p': -0.000000 , 'y': 0.000002 } }, -{ 'id' : 'table2_wheel_1', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_2', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_3', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_wheel_4', 'pos': { 'x': 0,'y': 0,'z': 0.06 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_front', 'pos': { 'x': 0,'y': 0, 'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_back', 'pos': { 'x': 0,'y': 0,'z': 0.45 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_left', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_body_right', 'pos': { 'x': 0,'y': 0,'z': 0.50 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'w': 1 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }}, -{ 'id' : 'table2_table_top', 'pos': { 'x': -0.100005, 'y': 1.204998, 'z': 0.885000 },'size': { 'length': 0.12,'width': 0.12,'height': 0.12 },'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 }, 'rpy': { 'r': 0.000000, 'p': -0.000000, 'y': 0.000003}}, -{ 'id': 'table1_right_panel' , 'pos': { 'x': -0.100004 , 'y': 0.552498 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table1_left_panel' , 'pos': { 'x': -0.100000 , 'y': -0.752502 , 'z': 0.880000 } , 'size': { 'length': 0.700000 , 'width': 0.500000 , 'height': 0.010000 } , 'orientation': { 'x': 0.000000 , 'y': 0.000000 , 'z': 0.000001 , 'w': 1.000000 } , 'color': { 'r': 0.15 , 'g': 0.15 , 'b': 0.15 } }, -{ 'id': 'table2_right_panel', 'pos': { 'x': -0.100007, 'y': 1.857498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'table2_front_panel', 'pos': { 'x': 0.552495, 'y': 1.205000 , 'z': 0.880000 },'size': { 'length': 0.500000,'width': 0.700000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, -{ 'id': 'arm1','type': 'ARM','pos': { 'x': -0.320002, 'y': -0.100003, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, -{ 'id': 'arm2','type': 'ARM','pos': { 'x': -0.320005, 'y': 1.204997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file diff --git a/src/mtc/results/-1560146588.yaml b/src/mtc/results/dummy.yaml similarity index 99% rename from src/mtc/results/-1560146588.yaml rename to src/mtc/results/dummy.yaml index cd82a34fcf19760455885691ba13f04d3472f0af..772e4c441b143bcafb3e869790381a6a8ec43a6d 100644 --- a/src/mtc/results/-1560146588.yaml +++ b/src/mtc/results/dummy.yaml @@ -22,4 +22,4 @@ { 'id': 'table2_right_panel', 'pos': { 'x': -0.000007, 'y': 2.057498 , 'z': 0.880000 },'size': { 'length': 0.700000,'width': 0.500000,'height': 0.010000 },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 0.15,'g': 0.15,'b': 0.15 } }, { 'id': 'arm1','type': 'ARM','pos': { 'x': -0.220002, 'y': 0.099997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } }, { 'id': 'arm2','type': 'ARM','pos': { 'x': -0.220005, 'y': 1.404997, 'z': 0.89 },'size': { },'orientation': { 'x': 0.000000, 'y': 0.000000, 'z': 0.000001, 'w': 1.000000 },'color': { 'r': 1.00,'g': 1.00,'b': 1.00 } } -]} \ No newline at end of file +]} diff --git a/src/mtc/src/base_routine.cpp b/src/mtc/src/base_routine.cpp index c222c7e92ea43e826cff10b6aebd6fb7d0500e68..5c02938fa082fcc034d75d226562a84639c43879 100644 --- a/src/mtc/src/base_routine.cpp +++ b/src/mtc/src/base_routine.cpp @@ -51,7 +51,6 @@ int main(int argc, char **argv){ if(it->first == "id"){ std::string top = it->second; if(top == "table1_table_top" ){ - ROS_INFO("Bin in Robot 1"); XmlRpc::XmlRpcValue::ValueStruct::const_iterator itt = resources[i].begin(); float h = 0; float w = 0; float l = 0; float x = 0; float y = 0; float z = 0; @@ -59,40 +58,76 @@ int main(int argc, char **argv){ for(; itt != resources[i].end(); ++itt){ if(itt->first == "size"){ - ROS_INFO("Bin in size von robot 1"); XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; + } + for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "length") l = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "width") w = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "height") h = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + if(ittt->first == "length") l = t; + if(ittt->first == "width") w = t; + if(ittt->first == "height") h = t; } } if(itt->first == "pos"){ - ROS_INFO("Bin in pos von robot 1"); XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; + } + for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "x") x = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "y") y = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "z") z = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + if(ittt->first == "x") x = t; + if(ittt->first == "y") y = t; + if(ittt->first == "z") z = t; } } if(itt->first == "orientation"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); - for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "x") qx = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "y") qy = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "z") qz = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "w") qw = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; } - ROS_INFO("Bin in orientation von robot 1"); - + for(; ittt != itt->second.end(); ++ittt){ + if(ittt->first == "x") qx = t; + if(ittt->first == "y") qy = t; + if(ittt->first == "z") qz = t; + if(ittt->first == "w") qw = t; + } } } - - Abstract_robot* robo = new Robot(std::string("panda_arm1"), tf2::Transform(tf2::Quaternion(qx,qy,qz,qw), tf2::Vector3(x,y, z * 0.5f)), tf2::Vector3(l,w,h)); + Abstract_robot* robo = new Robot(std::string("panda_arm1"), tf2::Transform(tf2::Quaternion(qx,qy,qz,qw), tf2::Vector3(0,0, z * 0.5f)), tf2::Vector3(l,w,h)); Robot* ceti = dynamic_cast<Robot*>(robo); ceti->set_observer_mask(wing_config::RML); ceti->add_rviz_markers(new visualization_msgs::MarkerArray()); @@ -108,42 +143,82 @@ int main(int argc, char **argv){ for(; itt != resources[i].end(); ++itt){ if(itt->first == "size"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; + } + for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "length") l = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "width") w = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "height") h = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + if(ittt->first == "length") l = t; + if(ittt->first == "width") w = t; + if(ittt->first == "height") h = t; } } if(itt->first == "pos"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; + } + for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "x") x = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "y") y = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "z") z = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + if(ittt->first == "x") x = t; + if(ittt->first == "y") y = t; + if(ittt->first == "z") z = t; } } if(itt->first == "orientation"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); - for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "x") qx = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "y") qy = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "z") qz = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "w") qw = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; } + for(; ittt != itt->second.end(); ++ittt){ + if(ittt->first == "x") qx = t; + if(ittt->first == "y") qy = t; + if(ittt->first == "z") qz = t; + if(ittt->first == "w") qw = t; + } } } - Abstract_robot* robo2 = new Robot(std::string("panda_arm2"), tf2::Transform(tf2::Quaternion(qx,qy,qz,qw), tf2::Vector3(x,y, z * 0.5f)), tf2::Vector3(l,w,h)); - Robot* ceti2 = dynamic_cast<Robot*>(robo2); - ceti2->set_observer_mask(wing_config::RML); - ceti2->add_rviz_markers(new visualization_msgs::MarkerArray()); - mediator->connect_robots(robo2); + Abstract_robot* robo = new Robot(std::string("panda_arm2"), tf2::Transform(tf2::Quaternion(qx,qy,qz,qw), tf2::Vector3(0,0, z * 0.5f)), tf2::Vector3(l,w,h)); + Robot* ceti = dynamic_cast<Robot*>(robo); + ceti->set_observer_mask(wing_config::RML); + ceti->add_rviz_markers(new visualization_msgs::MarkerArray()); + mediator->connect_robots(robo); } - if(top == "table1_right_panel" ) { XmlRpc::XmlRpcValue::ValueStruct::const_iterator itt = resources[i].begin(); float h = 0; float w = 0; float l = 0; @@ -152,32 +227,73 @@ int main(int argc, char **argv){ for(; itt != resources[i].end(); ++itt){ if(itt->first == "size"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; + } + for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "length") l = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "width") w = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "height") h = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + if(ittt->first == "length") l = t; + if(ittt->first == "width") w = t; + if(ittt->first == "height") h = t; } } if(itt->first == "pos"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; + } + for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "x") x = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "y") y = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "z") z = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + if(ittt->first == "x") x = t; + if(ittt->first == "y") y = t; + if(ittt->first == "z") z = t; } } - if(itt->first == "orientation"){ + if(itt->first == "orientation"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); - for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "x") qx = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "y") qy = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "z") qz = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "w") qw = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; } - } + for(; ittt != itt->second.end(); ++ittt){ + if(ittt->first == "x") qx = t; + if(ittt->first == "y") qy = t; + if(ittt->first == "z") qz = t; + if(ittt->first == "w") qw = t; + } + } } blueprints_per_robot[0][0].name_ = "table1_right_panel"; @@ -194,32 +310,73 @@ int main(int argc, char **argv){ for(; itt != resources[i].end(); ++itt){ if(itt->first == "size"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; + } + for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "length") l = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "width") w = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "height") h = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + if(ittt->first == "length") l = t; + if(ittt->first == "width") w = t; + if(ittt->first == "height") h = t; } } if(itt->first == "pos"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; + } + for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "x") x = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "y") y = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "z") z = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + if(ittt->first == "x") x = t; + if(ittt->first == "y") y = t; + if(ittt->first == "z") z = t; } } - if(itt->first == "orientation"){ + if(itt->first == "orientation"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); - for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "x") qx = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "y") qy = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "z") qz = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "w") qw = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; } - } + for(; ittt != itt->second.end(); ++ittt){ + if(ittt->first == "x") qx = t; + if(ittt->first == "y") qy = t; + if(ittt->first == "z") qz = t; + if(ittt->first == "w") qw = t; + } + } } blueprints_per_robot[0][1].name_ = "table1_front_panel"; @@ -236,32 +393,73 @@ int main(int argc, char **argv){ for(; itt != resources[i].end(); ++itt){ if(itt->first == "size"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; + } + for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "length") l = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "width") w = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "height") h = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + if(ittt->first == "length") l = t; + if(ittt->first == "width") w = t; + if(ittt->first == "height") h = t; } } if(itt->first == "pos"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; + } + for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "x") x = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "y") y = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "z") z = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + if(ittt->first == "x") x = t; + if(ittt->first == "y") y = t; + if(ittt->first == "z") z = t; } } - if(itt->first == "orientation"){ + if(itt->first == "orientation"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); - for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "x") qx = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "y") qy = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "z") qz = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "w") qw = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; } - } + for(; ittt != itt->second.end(); ++ittt){ + if(ittt->first == "x") qx = t; + if(ittt->first == "y") qy = t; + if(ittt->first == "z") qz = t; + if(ittt->first == "w") qw = t; + } + } } blueprints_per_robot[0][2].name_ = "table1_left_panel"; @@ -278,32 +476,73 @@ int main(int argc, char **argv){ for(; itt != resources[i].end(); ++itt){ if(itt->first == "size"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; + } + for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "length") l = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "width") w = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "height") h = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + if(ittt->first == "length") l = t; + if(ittt->first == "width") w = t; + if(ittt->first == "height") h = t; } } if(itt->first == "pos"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; + } + for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "x") x = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "y") y = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "z") z = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + if(ittt->first == "x") x = t; + if(ittt->first == "y") y = t; + if(ittt->first == "z") z = t; } } - if(itt->first == "orientation"){ + if(itt->first == "orientation"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); - for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "x") qx = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "y") qy = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "z") qz = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "w") qw = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; } - } + for(; ittt != itt->second.end(); ++ittt){ + if(ittt->first == "x") qx = t; + if(ittt->first == "y") qy = t; + if(ittt->first == "z") qz = t; + if(ittt->first == "w") qw = t; + } + } } blueprints_per_robot[1][0].name_ = "table2_right_panel"; @@ -320,32 +559,73 @@ int main(int argc, char **argv){ for(; itt != resources[i].end(); ++itt){ if(itt->first == "size"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; + } + for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "length") l = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "width") w = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "height") h = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + if(ittt->first == "length") l = t; + if(ittt->first == "width") w = t; + if(ittt->first == "height") h = t; } } if(itt->first == "pos"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; + } + for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "x") x = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "y") y = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "z") z = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + if(ittt->first == "x") x = t; + if(ittt->first == "y") y = t; + if(ittt->first == "z") z = t; } } - if(itt->first == "orientation"){ + if(itt->first == "orientation"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); - for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "x") qx = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "y") qy = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "z") qz = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "w") qw = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; } - } + for(; ittt != itt->second.end(); ++ittt){ + if(ittt->first == "x") qx = t; + if(ittt->first == "y") qy = t; + if(ittt->first == "z") qz = t; + if(ittt->first == "w") qw = t; + } + } } blueprints_per_robot[1][1].name_ = "table2_front_panel"; @@ -362,32 +642,75 @@ int main(int argc, char **argv){ for(; itt != resources[i].end(); ++itt){ if(itt->first == "size"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; + } + for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "length") l = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "width") w = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "height") h = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + if(ittt->first == "length") l = t; + if(ittt->first == "width") w = t; + if(ittt->first == "height") h = t; } } if(itt->first == "pos"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; + } + for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "x") x = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "y") y = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "z") z = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + if(ittt->first == "x") x = t; + if(ittt->first == "y") y = t; + if(ittt->first == "z") z = t; } } - if(itt->first == "orientation"){ + if(itt->first == "orientation"){ XmlRpc::XmlRpcValue::ValueStruct::const_iterator ittt = itt->second.begin(); - for(; ittt != itt->second.end(); ++ittt){ - if(ittt->first == "x") qx = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "y") qy = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "z") qz = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; - if(ittt->first == "w") qw = (ittt->second.getType() == XmlRpc::XmlRpcValue::TypeString) ? std::stof(ittt->second) : (double) ittt->second; + float t = 0; + switch (ittt->second.getType()) + { + case XmlRpc::XmlRpcValue::TypeInt: + t = static_cast<int>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeDouble: + t = static_cast<double>(ittt->second); + break; + case XmlRpc::XmlRpcValue::TypeString: + t = std::stof(ittt->second); + break; + default : + break; } - } + for(; ittt != itt->second.end(); ++ittt){ + if(ittt->first == "x") qx = t; + if(ittt->first == "y") qy = t; + if(ittt->first == "z") qz = t; + if(ittt->first == "w") qw = t; + } + } } blueprints_per_robot[1][2].name_ = "table2_left_panel"; @@ -395,10 +718,11 @@ int main(int argc, char **argv){ blueprints_per_robot[1][2].size_ = tf2::Vector3(l,w,h); b += std::pow(2, 2); } + } } } - mediator->set_wings(blueprints_per_robot); + // mediator->set_wings(blueprints_per_robot); mediator->mediate(); //map_loader->write_task(robo); diff --git a/src/mtc/src/cell_routine.cpp b/src/mtc/src/cell_routine.cpp index bf7c2b457e189dca8b17d44d99e212a03ed4ae72..162126265eb7fa49dc53befaa6b4d391dfc01108 100644 --- a/src/mtc/src/cell_routine.cpp +++ b/src/mtc/src/cell_routine.cpp @@ -387,8 +387,9 @@ int main(int argc, char **argv){ } } + + moveit_mediator->set_wings(blueprints_per_robot); - moveit_mediator->rewrite_task_template(); Moveit_robot* ceti1 = dynamic_cast<Moveit_robot*>(mediator->robots()[0]); Moveit_robot* ceti2 = dynamic_cast<Moveit_robot*>(mediator->robots()[1]); @@ -397,12 +398,10 @@ int main(int argc, char **argv){ int r1 = 0; int r2 = 1; moveit_mediator->build_wings(ia, r1); moveit_mediator->build_wings(ib, r2); - + //moveit::planning_interface::PlanningSceneInterface::applyCollisionObject() ceti1->notify(); ceti2->notify(); - moveit_mediator->publish_tables(); moveit_mediator->mediate(); - while (ros::ok()){ diff --git a/src/mtc/src/impl/mediator.cpp b/src/mtc/src/impl/mediator.cpp index 7e779988dd17e47deb4304bda608dfb0fed5f951..95aeeb10ec5f64c9e49ed8cb6251a17836954b71 100644 --- a/src/mtc/src/impl/mediator.cpp +++ b/src/mtc/src/impl/mediator.cpp @@ -10,6 +10,7 @@ bool Mediator::check_collision( const int& robot){ std::vector<int> count_v; Robot* r = dynamic_cast<Robot*>(robots_[robot]); count_v.resize(r->observers().size()+1); + std::string str; for(long unsigned int j = 0; j < objects_[robot].size(); j++){ visualization_msgs::Marker marker; @@ -29,7 +30,7 @@ bool Mediator::check_collision( const int& robot){ marker.scale.x = box_size.getX(); marker.scale.y = box_size.getY(); marker.scale.z = box_size.getZ(); - if(robots_[robot]->check_single_object_collision(objects_[robot][j])){ + if(robots_[robot]->check_single_object_collision(objects_[robot][j], str)){ marker.color.r = 0; marker.color.g = 1.0; marker.color.b = 0; @@ -92,7 +93,7 @@ void Mediator::mediate(){ ceti1->notify(); if (check_collision(0)) { - approximation(ceti1, j); + approximation(ceti1); } else { continue; } @@ -104,7 +105,7 @@ void Mediator::mediate(){ } } -void Mediator::approximation(Robot* robot, int& wings){ +void Mediator::approximation(Robot* robot){ ROS_INFO("assigne result to first robot..."); Robot* ceti = dynamic_cast<Robot*>(robots_[1]); int r1 = 1; diff --git a/src/mtc/src/impl/moveit_mediator.cpp b/src/mtc/src/impl/moveit_mediator.cpp index 786f5a28ec524f4da6f00f594872b4cc56d6dcd8..680147d065667bf03ba0a0f9caedcdadf240f463 100644 --- a/src/mtc/src/impl/moveit_mediator.cpp +++ b/src/mtc/src/impl/moveit_mediator.cpp @@ -5,23 +5,15 @@ -void Moveit_mediator::publish_tables(){ +void Moveit_mediator::publish_tables(moveit::planning_interface::PlanningSceneInterface& psi){ ros::WallDuration sleep_time(1.0); - - moveit_msgs::PlanningScene planning_scene; - planning_scene.is_diff = true; - for(long unsigned int i = 0; i < robots_.size();i++){ Moveit_robot* ceti = dynamic_cast<Moveit_robot*>(robots_[i]); for (moveit_msgs::CollisionObject* markers : ceti->coll_markers()) { - planning_scene.world.collision_objects.push_back(*markers); + psi.applyCollisionObject(*markers); sleep_time.sleep(); - } } - - - planning_scene_diff_publisher_.publish(planning_scene); - + } } void Moveit_mediator::load_robot_description(){ @@ -38,6 +30,9 @@ bool Moveit_mediator::check_collision(const int& robot){ void Moveit_mediator::mediate(){ // create christophs 'bottle' + moveit::planning_interface::PlanningSceneInterface psi; + publish_tables(psi); + moveit_msgs::CollisionObject bottle; bottle.id = "bottle"; bottle.header.frame_id = "world"; @@ -49,32 +44,49 @@ void Moveit_mediator::mediate(){ bottle.primitives[0].dimensions[1] = box_size.getY(); bottle.primitives[0].dimensions[2] = box_size.getZ(); - bottle.primitive_poses.resize(1); - bottle.primitive_poses[0].position.x = objects_[0].front().getOrigin().getX(); + bottle.primitive_poses[0].position.x = -0.3f; bottle.primitive_poses[0].position.y = -0.6f; bottle.primitive_poses[0].position.z = 0.9305f; bottle.primitive_poses[0].orientation.x = 0; bottle.primitive_poses[0].orientation.y = 0; bottle.primitive_poses[0].orientation.z = 0; bottle.primitive_poses[0].orientation.w = 1; - bottle.operation = bottle.ADD; - moveit_msgs::PlanningScene planning_scene; - planning_scene.is_diff = true; - planning_scene.world.collision_objects.push_back(bottle); - planning_scene_diff_publisher_.publish(planning_scene); - - - - + psi.applyCollisionObject(bottle); + rewrite_task_template(robots_[0], bottle); Yaml_Mtc_Parser parser = Yaml_Mtc_Parser(); moveit::task_constructor::Task task = parser.init_task(this->nh_); int max_planning_solutions = 1; // default one solution this->nh_.getParam("max_planning_solutions", max_planning_solutions); + try { + if (task.plan(max_planning_solutions)){ + moveit_msgs::MoveItErrorCodes execute_result; + + execute_result = task.execute(*task.solutions().front()); + //task.introspection().publishSolution(*task.solutions().front()); + /* + if (execute_result.val != moveit_msgs::MoveItErrorCodes::SUCCESS) { + ROS_INFO("irgendwas ging schief"); + } + */ + } + ROS_INFO("durch, print mich "); + } catch (const moveit::task_constructor::InitStageException& ex) { + std::cerr << "planning failed with exception" << std::endl << ex << task; + } + + /* + ROS_INFO("durch, print mich daddy"); + tf2::Vector3 source2(0.1, 1, 0.9305); + rewrite_task_template(robots_[1], source2); + + task.clear(); + task = parser.init_task(this->nh_); + this->nh_.getParam("max_planning_solutions", max_planning_solutions); try { if (task.plan(max_planning_solutions)) { task.introspection().publishSolution(*task.solutions().front()); @@ -83,6 +95,7 @@ void Moveit_mediator::mediate(){ std::cerr << "planning failed with exception" << std::endl << ex << task; } + */ ros::waitForShutdown(); }; @@ -99,50 +112,72 @@ void Moveit_mediator::build_wings(std::bitset<3>& wing, int& robot){ } } -void Moveit_mediator::rewrite_task_template(){ +void Moveit_mediator::rewrite_task_template(Abstract_robot* r, moveit_msgs::CollisionObject& source){ + tf2::Transform t(tf2::Quaternion(source.primitive_poses[0].orientation.x, source.primitive_poses[0].orientation.y, source.primitive_poses[0].orientation.z, source.primitive_poses[0].orientation.w), tf2::Vector3(source.primitive_poses[0].position.x, source.primitive_poses[0].position.y, source.primitive_poses[0].position.z)); + tf2::Transform target(tf2::Quaternion(0,0,0,1), tf2::Vector3(0.1f, 0.6f, 0.9305f)); + + XmlRpc::XmlRpcValue task; nh_.getParam("task/stages", task); - /* - task: - name: Pick and Place test - properties: - group: panda_arm1 - eef: hand_1 - hand_grasping_frame: panda_1_link8 - ik_frame: panda_1_link8 - hand: hand_1 - */ - nh_.setParam("/task/properties/group", "panda_arm1"); - nh_.setParam("/task/properties/eef", "hand_1"); - nh_.setParam("/task/properties/hand_grasping_frame", "panda_1_link8"); - nh_.setParam("/task/properties/ik_frame", "panda_1_link8"); - nh_.setParam("/task/properties/hand", "hand_1"); + std::stringstream ss; + ss << "hand_" << r->name().back(); + std::string hand = ss.str(); + std::stringstream sss; + sss << "panda_" << r->name().back() << "_link8"; + std::string last_link = sss.str(); - for(int i = 0; i < task.size(); i++){ - XmlRpc::XmlRpcValue::ValueStruct::const_iterator it = task[i].begin(); - for(; it != task[i].end(); ++it){ - } + std::string support_surface1 = "nichts"; + std::string support_surface2 = "nichts"; + + + for (Abstract_robot* ar : robots_){ + std::string str; + if(ar->check_single_object_collision(t, str)) support_surface1 = str; + if(ar->check_single_object_collision(target, str)) support_surface2= str; } - XmlRpc::XmlRpcValue a, b, c, d, e; - a["group"] = "hand_1"; - e["joint_model_group_name"] = "hand_1"; + ROS_INFO("%f %f %f source", t.getOrigin().getX(), t.getOrigin().getY(), t.getOrigin().getZ()); + + ROS_INFO("surface1 %s", support_surface1.c_str()); + ROS_INFO("surface2 %s", support_surface2.c_str()); + + + nh_.setParam("/task/properties/group", r->name()); + nh_.setParam("/task/properties/eef", hand); + nh_.setParam("/task/properties/hand_grasping_frame", last_link); + nh_.setParam("/task/properties/ik_frame", last_link); + nh_.setParam("/task/properties/hand", hand); + + XmlRpc::XmlRpcValue a, b, c, d, e, h; + a["group"] = hand; + e["joint_model_group_name"] = hand; b = task[4]["stages"]; + b[1]["stage"]["properties"]["object"] = source.id; b[3]["properties"] = a; + b[2]["set"]["allow_collisions"]["first"] = source.id; b[2]["set"]["allow_collisions"]["second"] = e; c = task[6]["stages"]; - c[2]["properties"] = a; - c[5]["properties"] = a; - c[3]["set"]["allow_collisions"]["second"] = e; - + + c[0]["set"]["allow_collisions"]["first"] = source.id; + c[0]["set"]["allow_collisions"]["second"] = support_surface2; + c[3]["properties"] = a; + c[6]["properties"] = a; + c[4]["set"]["allow_collisions"]["first"] = source.id; + c[4]["set"]["allow_collisions"]["second"] = e; + + h["x"] = static_cast<double>(0); + h["y"] = static_cast<double>(-0.5f); + h["z"] = static_cast<double>(0.9305f); + c[2]["stage"]["set"]["pose"]["point"]= h; + task[2]["properties"] = a; XmlRpc::XmlRpcValue connect, f, g; - f["panda_arm1"] = "sampling"; + f[r->name()] = "sampling"; g["source"] = "PARENT"; connect["type"] = "Connect"; connect["group_planner_vector"] = f; @@ -152,24 +187,30 @@ void Moveit_mediator::rewrite_task_template(){ a.clear(); e.clear(); - a["link"] = "panda_1_link8"; + a["link"] = last_link; a["min_distance"] = 0.07; a["max_distance"] = 0.2; - c[4]["properties"] = a; + c[5]["properties"] = a; b[0]["properties"] = a; a["min_distance"] = 0.1; a["max_distance"] = 0.2; - c[0]["properties"] = a; + c[1]["properties"] = a; e["object"] = "bottle"; - e["link"] = "panda_1_link8"; + e["link"] = last_link; b[4]["set"]["attach_object"] = e; - c[3]["set"]["detach_object"] = e; - c[1]["set"]["ik_frame"]["link"] = "panda_1_link8"; - c[4]["set"]["direction"]["vector"]["header"]["frame_id"] = "panda_1_link8"; - b[1]["set"]["ik_frame"]["link"] = "panda_1_link8"; - b[5]["set"]["ik_frame"]["link"] = "panda_1_link8"; - b[0]["set"]["direction"]["vector"]["header"]["frame_id"] = "panda_1_link8"; + c[4]["set"]["detach_object"] = e; + c[2]["set"]["ik_frame"]["link"] = last_link; + c[5]["set"]["direction"]["vector"]["header"]["frame_id"] = last_link; + b[1]["set"]["ik_frame"]["link"] = last_link; + b[6]["set"]["ik_frame"]["link"] = last_link; + b[0]["set"]["direction"]["vector"]["header"]["frame_id"] = last_link; + + b[5]["set"]["allow_collisions"]["first"] = source.id; + b[5]["set"]["allow_collisions"]["second"] = support_surface1; + b[7]["set"]["allow_collisions"]["first"] = source.id; + b[7]["set"]["allow_collisions"]["second"] = support_surface1; + task[6]["stages"] = c; task[4]["stages"] = b; diff --git a/src/mtc/src/impl/robot.cpp b/src/mtc/src/impl/robot.cpp index 292517c3d229616ea0e60f922edd5b0ec000282c..d444e069bda77aae45b2826b1e18689c2d1ac037 100644 --- a/src/mtc/src/impl/robot.cpp +++ b/src/mtc/src/impl/robot.cpp @@ -63,13 +63,11 @@ void Robot::workload_checker(std::vector<int>& count_vector, tf2::Transform& obj float full_area = area_calculation(A,B,C) + area_calculation(A,D,C); float sum = area_calculation(A,obj,D) + area_calculation(D,obj,C) + area_calculation(C,obj,B) + area_calculation(obj, B, A); if ((std::floor(sum*100)/100.f) <= full_area) count_vector.back()++; return; - - } -bool Robot::check_single_object_collision(tf2::Transform& obj){ +bool Robot::check_single_object_collision(tf2::Transform& obj, std::string& str){ tf2::Transform A = tf_ * root_tf_ * robot_root_bounds_[0]; tf2::Transform B = tf_ * root_tf_ * robot_root_bounds_[1]; @@ -80,7 +78,8 @@ bool Robot::check_single_object_collision(tf2::Transform& obj){ float sum = area_calculation(A,obj,D) + area_calculation(D,obj,C) + area_calculation(C,obj,B) + area_calculation(obj, B, A); if ((std::floor(sum*100)/100.f) <= full_area) {return false; } - + std::stringstream ss; + ss << "base_" << name_.back(); A = tf_ * bounds_[0]; B = tf_ * bounds_[1]; C = tf_ * bounds_[2]; @@ -88,7 +87,10 @@ bool Robot::check_single_object_collision(tf2::Transform& obj){ full_area = area_calculation(A,B,C) + area_calculation(A,D,C); sum = area_calculation(A,obj,D) + area_calculation(D,obj,C) + area_calculation(C,obj,B) + area_calculation(obj, B, A); - if ((std::floor(sum*100)/100.f) <= full_area) return true; + if ((std::floor(sum*100)/100.f) <= full_area){ + str = ss.str(); + return true; + } if (!observers_.empty()){ std::vector<Abstract_robot_element*>::const_iterator it = observers_.begin(); @@ -104,6 +106,7 @@ bool Robot::check_single_object_collision(tf2::Transform& obj){ sum = area_calculation(A,obj,D) + area_calculation(D,obj,C) + area_calculation(C,obj,B) + area_calculation(obj, B, A); if ((std::floor(sum*100)/100.f) <= full_area) { + str = ceti->name(); return true; } else { ++it; @@ -118,7 +121,7 @@ void Robot::reset(){ access_fields_.clear(); generate_access_fields(); - tf_ = tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(0,0,0.4425f)); + tf_ = tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(0,0, tf().getOrigin().getZ())); } void Robot::notify(){ diff --git a/src/mtc/src/impl/wing_moveit_decorator.cpp b/src/mtc/src/impl/wing_moveit_decorator.cpp index 6943b43df32ac3ff4ac9053742f4ed3edac9df0a..e026b132b48f1c4652a97baa75d67fbed85214df 100644 --- a/src/mtc/src/impl/wing_moveit_decorator.cpp +++ b/src/mtc/src/impl/wing_moveit_decorator.cpp @@ -13,7 +13,7 @@ void Wing_moveit_decorator::output_filter() { tf2::Quaternion world_quat = wing->world_tf().getRotation().normalized(); - markers_->id = std::to_string(*((int*)(&next_))); + markers_->id = wing->name(); markers_->header.frame_id = "world"; markers_->primitives.resize(1);