Skip to content
Snippets Groups Projects
Commit f498381f authored by KingMaZito's avatar KingMaZito
Browse files

mtc fully integrated, urdf changed, results are store as usual dummy files

parent 7491de87
No related branches found
No related tags found
No related merge requests found
Pipeline #14923 failed
Showing
with 277 additions and 262 deletions
/home/matteo/ws_panda/devel/./cmake.lock 42 /home/matteo/ws_panda/devel/./cmake.lock 42
/home/matteo/reachability/devel/./cmake.lock 12715 /home/matteo/reachability/devel/./cmake.lock 14204
/home/matteo/reachability/devel/lib/libmoveit_grasps.so 79 /home/matteo/reachability/devel/lib/libmoveit_grasps.so 79
/home/matteo/reachability/devel/lib/libmoveit_grasps_filter.so 79 /home/matteo/reachability/devel/lib/libmoveit_grasps_filter.so 79
...@@ -38,7 +38,8 @@ ...@@ -38,7 +38,8 @@
"${workspaceFolder}/mtc/include/impl/ho", "${workspaceFolder}/mtc/include/impl/ho",
"${workspaceFolder}/mtc/src", "${workspaceFolder}/mtc/src",
"${workspaceFolder}/yaml_to_mtc/include", "${workspaceFolder}/yaml_to_mtc/include",
"${workspaceFolder}/moveit_task_constructor/core/include" "${workspaceFolder}/moveit_task_constructor/core/include",
"${workspaceFolder}/moveit_task_constructor/"
], ],
"name": "ROS" "name": "ROS"
} }
......
...@@ -10,33 +10,32 @@ ...@@ -10,33 +10,32 @@
<link name="world" /> <link name="world" />
<xacro:property name="yaml_file" value="$(find mtc)/results/-671106318.yaml" /> <xacro:property name="yaml_file" value="$(find mtc)/results/-229104537.yaml" />
<xacro:property name="props" value="${xacro.load_yaml(yaml_file)}" /> <xacro:property name="props" value="${xacro.load_yaml(yaml_file)}" />
<xacro:property name="x1" value="${props['Robot_arm1']['pos_x']}" /> <xacro:property name="x1" value="${props['objects'][8]['pos']['x']}" />
<xacro:property name="y1" value="${props['Robot_arm1']['pos_y']}" /> <xacro:property name="y1" value="${props['objects'][8]['pos']['y']}" />
<xacro:property name="z1" value="${props['Robot_arm1']['pos_z']}" /> <xacro:property name="z1" value="${props['objects'][8]['pos']['z']}" />
<xacro:property name="rpy1" value="${props['Robot_arm1']['rpy']}" /> <xacro:property name="rpy1" value="${props['objects'][8]['rpy']['r']} ${props['objects'][8]['rpy']['p']} ${props['objects'][8]['rpy']['y']}" />
<xacro:property name="x2" value="${props['objects'][17]['pos']['x']}" />
<xacro:property name="x2" value="${props['Robot_arm2']['pos_x']}" /> <xacro:property name="y2" value="${props['objects'][17]['pos']['y']}" />
<xacro:property name="y2" value="${props['Robot_arm2']['pos_y']}" /> <xacro:property name="z2" value="${props['objects'][17]['pos']['z']}" />
<xacro:property name="z2" value="${props['Robot_arm2']['pos_z']}" /> <xacro:property name="rpy2" value="${props['objects'][17]['rpy']['r']} ${props['objects'][17]['rpy']['p']} ${props['objects'][17]['rpy']['y']}" />
<xacro:property name="rpy2" value="${props['Robot_arm2']['rpy']}" />
<!-- Dummy Link --> <!-- Dummy Link -->
<joint name="base_joint1" type="fixed"> <joint name="base_joint1" type="fixed">
<parent link="world" /> <parent link="world" />
<child link="base_1" /> <child link="base_1" />
<origin xyz="${x1} ${y1} ${z1}" rpy="${rpy1}"/> <origin xyz="${x1} ${y1} ${z1 * 0.5}" rpy="${rpy1}"/>
<axis xyz="0 0 1"/> <axis xyz="0 0 1"/>
</joint> </joint>
<joint name="base_joint2" type="fixed"> <joint name="base_joint2" type="fixed">
<parent link="world" /> <parent link="world" />
<child link="base_2" /> <child link="base_2" />
<origin xyz="${x2} ${y2} ${z2}" rpy="${rpy2}"/> <origin xyz="${x2} ${y2} ${z2 * 0.5}" rpy="${rpy2}"/>
<axis xyz="0 0 1"/> <axis xyz="0 0 1"/>
</joint> </joint>
...@@ -45,7 +44,7 @@ ...@@ -45,7 +44,7 @@
<visual> <visual>
<origin xyz="0 0 0" rpy="0 0 0"/> <origin xyz="0 0 0" rpy="0 0 0"/>
<geometry> <geometry>
<box size="0.8 0.8 0.885" /> <box size="0.8 0.8 ${z1}" />
</geometry> </geometry>
<material name="White"> <material name="White">
<color rgba="1.0 1.0 1.0 1.0"/> <color rgba="1.0 1.0 1.0 1.0"/>
...@@ -54,7 +53,7 @@ ...@@ -54,7 +53,7 @@
<collision> <collision>
<origin xyz="0 0 0" rpy="0 0 0"/> <origin xyz="0 0 0" rpy="0 0 0"/>
<geometry> <geometry>
<box size="0.8 0.8 0.885" /> <box size="0.8 0.8 ${z1}" />
</geometry> </geometry>
</collision> </collision>
</link> </link>
...@@ -63,7 +62,7 @@ ...@@ -63,7 +62,7 @@
<visual> <visual>
<origin xyz="0 0 0" rpy="0 0 0"/> <origin xyz="0 0 0" rpy="0 0 0"/>
<geometry> <geometry>
<box size="0.8 0.8 0.885" /> <box size="0.8 0.8 ${z2}" />
</geometry> </geometry>
<material name="White"> <material name="White">
<color rgba="1.0 1.0 1.0 1.0"/> <color rgba="1.0 1.0 1.0 1.0"/>
...@@ -72,18 +71,18 @@ ...@@ -72,18 +71,18 @@
<collision> <collision>
<origin xyz="0 0 0" rpy="0 0 0"/> <origin xyz="0 0 0" rpy="0 0 0"/>
<geometry> <geometry>
<box size="0.8 0.8 0.885" /> <box size="0.8 0.8 ${z2}" />
</geometry> </geometry>
</collision> </collision>
</link> </link>
<!-- right arm with gripper --> <!-- right arm with gripper -->
<xacro:panda_arm arm_id="$(arg arm_id_1)" connected_to="base_1" xyz="-0.22 0 ${z1}" /> <xacro:panda_arm arm_id="$(arg arm_id_1)" connected_to="base_1" xyz="-0.22 0 ${z1 * 0.5}" />
<xacro:hand ns="$(arg arm_id_1)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id_1)_link8" /> <xacro:hand ns="$(arg arm_id_1)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id_1)_link8" />
<!-- left arm with gripper --> <!-- left arm with gripper -->
<xacro:panda_arm arm_id="$(arg arm_id_2)" connected_to="base_2" xyz="-0.22 0 ${z2}" /> <xacro:panda_arm arm_id="$(arg arm_id_2)" connected_to="base_2" xyz="-0.22 0 ${z2 * 0.5}" />
<xacro:hand ns="$(arg arm_id_2)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id_2)_link8"/> <xacro:hand ns="$(arg arm_id_2)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id_2)_link8"/>
</robot> </robot>
...@@ -14,9 +14,12 @@ ...@@ -14,9 +14,12 @@
#include <yaml-cpp/yaml.h> #include <yaml-cpp/yaml.h>
#include <fstream> #include <fstream>
#include "impl/abstract_robot.h"
#include "impl/abstract_strategy.h" #include "impl/abstract_strategy.h"
class Abstract_strategy; class Abstract_strategy;
class Abstract_robot;
class Abstract_map_loader{ class Abstract_map_loader{
protected: protected:
...@@ -47,7 +50,7 @@ class Abstract_map_loader{ ...@@ -47,7 +50,7 @@ class Abstract_map_loader{
inline std::vector<std::vector<pcl::PointCloud< pcl::PointXYZ >::Ptr>>& target_cloud () { return target_cloud_;} inline std::vector<std::vector<pcl::PointCloud< pcl::PointXYZ >::Ptr>>& target_cloud () { return target_cloud_;}
static std::vector<pcl::PointXYZ> create_pcl_box(); static std::vector<pcl::PointXYZ> create_pcl_box();
virtual void write_task()=0; virtual void write_task(Abstract_robot* robot)=0;
virtual std::vector<std::vector<pcl::PointXYZ>> base_calculation()=0; virtual std::vector<std::vector<pcl::PointXYZ>> base_calculation()=0;
}; };
#endif #endif
...@@ -20,9 +20,10 @@ ...@@ -20,9 +20,10 @@
#define M_POS tf2::Vector3(0.6525f,0,0.4425f-0.005f) #define M_POS tf2::Vector3(0.6525f,0,0.4425f-0.005f)
struct wing_BP { struct wing_BP {
std::string name_;
tf2::Transform pos_; tf2::Transform pos_;
tf2::Vector3 size_; tf2::Vector3 size_;
wing_BP(tf2::Transform pos, tf2::Vector3 size) : pos_(pos), size_(size){}; wing_BP(std::string name, tf2::Transform pos, tf2::Vector3 size) : name_ (name), pos_(pos), size_(size){};
}; };
...@@ -41,9 +42,9 @@ class Abstract_mediator { ...@@ -41,9 +42,9 @@ class Abstract_mediator {
public: public:
Abstract_mediator(std::vector<std::vector<tf2::Transform>> objects, ros::Publisher* pub) : objects_(objects), pub_(pub){ Abstract_mediator(std::vector<std::vector<tf2::Transform>> objects, ros::Publisher* pub) : objects_(objects), pub_(pub){
wings_.push_back(wing_BP(tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(0,0.6525f,0.4425f -0.005f)), right_size)); 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(tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(0.6525f,0,0.4425f-0.005f)), mid_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(tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(0,-0.6525f,0.4425f -0.005f)), left_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));
} }
inline void connect_robots(Abstract_robot* robot) {robots_.push_back(robot); ROS_INFO("%s connected...", robot->name().c_str());} inline void connect_robots(Abstract_robot* robot) {robots_.push_back(robot); ROS_INFO("%s connected...", robot->name().c_str());}
......
...@@ -11,7 +11,7 @@ class Map_loader : public Abstract_map_loader { ...@@ -11,7 +11,7 @@ class Map_loader : public Abstract_map_loader {
public: public:
Map_loader(XmlRpc::XmlRpcValue& map_data, XmlRpc::XmlRpcValue& target_data); Map_loader(XmlRpc::XmlRpcValue& map_data, XmlRpc::XmlRpcValue& target_data);
std::vector<std::vector<pcl::PointXYZ>> base_calculation() override; std::vector<std::vector<pcl::PointXYZ>> base_calculation() override;
void write_task() override; void write_task(Abstract_robot* robot) override;
}; };
#endif #endif
\ No newline at end of file
...@@ -6,17 +6,20 @@ ...@@ -6,17 +6,20 @@
class Wing : public Abstract_robot_element{ class Wing : public Abstract_robot_element{
private: private:
std::string name_;
tf2::Vector3 size_; tf2::Vector3 size_;
std::vector<tf2::Transform> bounds_; std::vector<tf2::Transform> bounds_;
public: public:
Wing(tf2::Transform tf, tf2::Vector3 size) : size_(size){ Wing(std::string name, tf2::Transform tf, tf2::Vector3 size) : size_(size), name_(name){
relative_tf_ = tf; relative_tf_ = tf;
bounds_.push_back(tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(size_.getX()/2.f, size_.getY()/2.f,0))); //++ bounds_.push_back(tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(size_.getX()/2.f, size_.getY()/2.f,0))); //++
bounds_.push_back(tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(size_.getX()/2.f, size_.getY()/-2.f,0))); //+- bounds_.push_back(tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(size_.getX()/2.f, size_.getY()/-2.f,0))); //+-
bounds_.push_back(tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(size_.getX()/-2.f, size_.getY()/-2.f,0))); //-- bounds_.push_back(tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(size_.getX()/-2.f, size_.getY()/-2.f,0))); //--
bounds_.push_back(tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(size_.getX()/-2.f, size_.getY()/2.f,0))); //-+ bounds_.push_back(tf2::Transform(tf2::Quaternion(0,0,0,1), tf2::Vector3(size_.getX()/-2.f, size_.getY()/2.f,0))); //-+
} }
inline std::string& name() {return name_;}
inline tf2::Vector3 size(){ return size_;} inline tf2::Vector3 size(){ return size_;}
inline std::vector<tf2::Transform>& bounds() {return bounds_;} inline std::vector<tf2::Transform>& bounds() {return bounds_;}
void update(tf2::Transform& tf) override {this->calc_world_tf(tf);} void update(tf2::Transform& tf) override {this->calc_world_tf(tf);}
......
<launch> <launch>
<!--<include file="$(find panda_moveit_config)/launch/demo.launch"></include> --> <!--<include file="$(find panda_moveit_config)/launch/demo.launch"></include> -->
<rosparam command="load" file="$(find mtc)/results/-671106318.yaml"/> <rosparam command="load" file="$(find mtc)/results/-229104537.yaml"/>
<rosparam command="load" file="$(find mtc)/mtc_task_file/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)/maps/dummy.yaml"/>
<rosparam command="load" file="$(find mtc)/descriptions/dummy.yaml"/> <rosparam command="load" file="$(find mtc)/descriptions/dummy.yaml"/>
......
planners: planners:
- id: "cartesian" - id: cartesian
type: "CartesianPath" type: CartesianPath
- id: "sampling" - id: sampling
type: "PipelinePlanner" type: PipelinePlanner
properties: properties:
step_size: 0.005 step_size: 0.005
goal_joint_tolerance: 0.00001 goal_joint_tolerance: 9.999999747378752e-06
- id: "interpolation" - id: interpolation
type: "JointInterpolationPlanner" type: JointInterpolationPlanner
task: task:
name: "Pick and Place test" name: Pick and Place test
properties: properties:
group: "panda_arm1" group: panda_arm1
eef: "hand_1" eef: hand_1
hand_grasping_frame: "panda_1_link8" hand_grasping_frame: panda_1_link8
ik_frame: "panda_1_link8" ik_frame: panda_1_link8
hand: "hand_1" hand: hand_1
stages: stages:
- name: "current" - name: current
type: "CurrentState" type: CurrentState
- name: "move to ready" - name: move to ready
type: "MoveTo" type: MoveTo
id: "ready" id: ready
planner: "sampling" planner: sampling
propertiesConfigureInitFrom: propertiesConfigureInitFrom:
source: "PARENT" source: PARENT
values: values:
- "group" - group
set: set:
goal: "ready" goal: ready
- type: "MoveTo" - type: MoveTo
planner: "sampling" planner: sampling
id: "hand_open" id: hand_open
properties: properties:
group: "hand_1" group: hand_1
set: set:
goal: "open" goal: open
- type: "Connect" - type: Connect
group_planner_vector: group_planner_vector:
panda_arm1: "sampling" panda_arm1: sampling
propertiesConfigureInitFrom: propertiesConfigureInitFrom:
source: "PARENT" source: PARENT
- type: SerialContainer - type: SerialContainer
name: "grasp" name: grasp
properties_exposeTo: properties_exposeTo:
source: "task" source: task
values: ["eef", "hand", "group", "ik_frame"] values: [eef, hand, group, ik_frame]
propertiesConfigureInitFrom: propertiesConfigureInitFrom:
source: "PARENT" source: PARENT
values: ["eef", "hand", "group", "ik_frame"] values: [eef, hand, group, ik_frame]
stages: stages:
- type: "MoveRelative" - type: MoveRelative
planner: "cartesian" planner: cartesian
properties: properties:
link: "panda_1_link8" link: panda_1_link8
min_distance: 0.07 min_distance: 0.07
max_distance: 0.2 max_distance: 0.2
propertiesConfigureInitFrom: propertiesConfigureInitFrom:
source: "PARENT" source: PARENT
values: ["group"] values: [group]
set: set:
direction: direction:
vector: {x: 0.0, y: 0.0, z: 1.0, header: {frame_id: "panda_1_link8"}} vector: {x: 0.0, y: 0.0, z: 1.0, header: {frame_id: panda_1_link8}}
- type: "ComputeIK" - type: ComputeIK
properties: {max_ik_solutions: 5} properties: {max_ik_solutions: 5}
set: set:
ik_frame: ik_frame:
isometry: isometry:
translation: {x: 0.1, y: 0.0, z: 0.0} translation: {x: 0.1, y: 0.0, z: 0.0}
quaternion: {r: 1.571, p: 0.785, y: 1.571} quaternion: {r: 1.571, p: 0.785, y: 1.571}
link: "panda_1_link8" link: panda_1_link8
propertiesConfigureInitFrom: propertiesConfigureInitFrom:
- source: "PARENT" - source: PARENT
values: ["eef", "group"] values: [eef, group]
- source: "INTERFACE" - source: INTERFACE
values: ["target_pose"] values: [target_pose]
stage: stage:
type: "GenerateGraspPose" type: GenerateGraspPose
propertiesConfigureInitFrom: propertiesConfigureInitFrom:
source: "PARENT" source: PARENT
properties: properties:
object: "bottle" object: bottle
angle_delta: 1.571 angle_delta: 1.571
pregrasp: "open" pregrasp: open
set: set:
monitored_stage: "ready" monitored_stage: ready
- type: "ModifyPlanningScene" - type: ModifyPlanningScene
set: set:
allow_collisions: allow_collisions:
first: "bottle" first: bottle
second: second:
joint_model_group_name: "hand_1" joint_model_group_name: hand_1
allow: true allow: true
- type: "MoveTo" - type: MoveTo
planner: "sampling" planner: sampling
properties: properties:
group: "hand_1" group: hand_1
set: set:
goal: "close" goal: close
- type: "ModifyPlanningScene" - type: ModifyPlanningScene
set: set:
attach_object: attach_object:
object: "bottle" object: bottle
link: "panda_1_link8" link: panda_1_link8
- type: "MoveRelative" - type: MoveRelative
planner: "cartesian" planner: cartesian
id: "pick_up" id: pick_up
propertiesConfigureInitFrom: propertiesConfigureInitFrom:
source: "PARENT" source: PARENT
values: ["group"] values: [group]
properties: properties:
min_distance: 0.1 min_distance: 0.1
max_distance: 0.2 max_distance: 0.2
set: set:
ik_frame: ik_frame:
link: "panda_1_link8" link: panda_1_link8
direction: direction:
vector: {x: 0.0, y: 0.0, z: 1.0} vector: {x: 0.0, y: 0.0, z: 1.0}
- type: "Connect" - type: Connect
group_planner_vector: group_planner_vector:
panda_arm1: "sampling" panda_arm1: sampling
propertiesConfigureInitFrom: propertiesConfigureInitFrom:
source: "PARENT" source: PARENT
- type: SerialContainer - type: SerialContainer
name: "place" name: place
properties_exposeTo: properties_exposeTo:
source: "task" source: task
values: ["eef", "hand", "group", "ik_frame"] values: [eef, hand, group, ik_frame]
propertiesConfigureInitFrom: propertiesConfigureInitFrom:
source: "PARENT" source: PARENT
stages: stages:
- type: "MoveRelative" - type: MoveRelative
planner: "cartesian" planner: cartesian
properties: properties:
link: "panda_1_link8" link: panda_1_link8
min_distance: 0.1 min_distance: 0.1
max_distance: 0.2 max_distance: 0.2
propertiesConfigureInitFrom: propertiesConfigureInitFrom:
source: "PARENT" source: PARENT
values: ["group"] values: [group]
set: set:
direction: direction:
vector: {x: 0.0, y: 0.0, z: -1.0} vector: {x: 0.0, y: 0.0, z: -1.0}
- type: "ComputeIK" - type: ComputeIK
properties: {max_ik_solutions: 5} properties: {max_ik_solutions: 5}
set: set:
ik_frame: ik_frame:
isometry: isometry:
translation: {x: 0.1, y: 0.0, z: 0.0} translation: {x: 0.1, y: 0.0, z: 0.0}
quaternion: {r: 1.571, p: 0.785, y: 1.571} quaternion: {r: 1.571, p: 0.785, y: 1.571}
link: "panda_1_link8" link: panda_1_link8
propertiesConfigureInitFrom: propertiesConfigureInitFrom:
- source: "PARENT" - source: PARENT
values: ["eef", "group"] values: [eef, group]
- source: "INTERFACE" - source: INTERFACE
values: ["target_pose"] values: [target_pose]
stage: stage:
type: "GeneratePose" type: GeneratePose
set: set:
monitored_stage: "pick_up" monitored_stage: pick_up
pose: pose:
point: {x: 0.1, y: 0.3, z: 0.9305} point: {x: 0.200000, y: 0.400000, z: 0.9305}
orientation: {x: 0.0, y: 0.0, z: 0.0, w: 1.0} orientation: {x: 0.0, y: 0.0, z: 0.0, w: 1.0}
- type: "MoveTo" - type: MoveTo
planner: "sampling" planner: sampling
properties: properties:
group: "hand_1" group: hand_1
set: set:
goal: "open" goal: open
- type: "ModifyPlanningScene" - type: ModifyPlanningScene
set: set:
detach_object: detach_object:
object: "bottle" object: bottle
link: "panda_1_link8" link: panda_1_link8
allow_collisions: allow_collisions:
first: "bottle" first: bottle
second: second:
joint_model_group_name: "hand_1" joint_model_group_name: hand_1
allow: false allow: false
- type: "MoveRelative" - type: MoveRelative
planner: "cartesian" planner: cartesian
properties: properties:
link: "panda_1_link8" link: panda_1_link8
min_distance: 0.07 min_distance: 0.07
max_distance: 0.2 max_distance: 0.2
propertiesConfigureInitFrom: propertiesConfigureInitFrom:
source: "PARENT" source: PARENT
values: ["group"] values: [group]
set: set:
direction: direction:
vector: {x: 0.0, y: 0.0, z: -1.0, header: {frame_id: panda_1_link8}} vector: {x: 0.0, y: 0.0, z: -1.0, header: {frame_id: panda_1_link8}}
- type: "MoveTo" - type: MoveTo
planner: "sampling" planner: sampling
properties: properties:
group: "hand_1" group: hand_1
set: set:
goal: "close" goal: close
- name: "move to ready" - name: move to ready
type: "MoveTo" type: MoveTo
planner: "sampling" planner: sampling
propertiesConfigureInitFrom: propertiesConfigureInitFrom:
source: "PARENT" source: PARENT
values: values:
- "group" - group
set: set:
goal: "ready" goal: ready
max_planning_solutions: 10 max_planning_solutions: 10
\ No newline at end of file
{ '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.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.000006, 'y': 1.699998, '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.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.000000 , '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_left_panel', 'pos': { 'x': -0.000004, 'y': 1.047498 , '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.220006, 'y': 1.699997, '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
{ '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.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.000005, '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.000004 , '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.000000 , '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.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': 'table2_front_panel', 'pos': { 'x': 0.652495, '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.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
{ '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.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.000005, '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.000004 , '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.000000 , '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.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
Robot_arm1:
pos_x: -2.041459083557129e-06
pos_y: -2.041459083557129e-06
pos_z: 0.4424999952316284
q_x: 0
q_y: 0
q_z: 0.04361940470594575
q_w: 0.9990482208247503
rpy: 0.000000 -0.000000 0.087266
wings: 7
Robot_arm2:
pos_x: -0.1137403263029958
pos_y: 1.300031983349814
pos_z: 0.4424999952316284
q_x: 0
q_y: 0
q_z: 0.7372773633019241
q_w: 0.6755901787049325
rpy: 0.000000 -0.000000 1.658063
wings: 7
\ No newline at end of file
Robot_arm1:
pos_x: -2.041459083557129e-06
pos_y: -2.041459083557129e-06
pos_z: 0.4424999952316284
q_x: 0
q_y: 0
q_z: 0.04361940470594575
q_w: 0.9990482208247503
rpy: 0.000000 -0.000000 0.087266
wings: 7
Robot_arm2:
pos_x: -0.1137403263029958
pos_y: 1.300031983349814
pos_z: 0.4424999952316284
q_x: 0
q_y: 0
q_z: 0.7372773633019241
q_w: 0.6755901787049325
rpy: 0.000000 -0.000000 1.658063
wings: 6
\ No newline at end of file
Robot_arm1:
pos_x: -2.041459083557129e-06
pos_y: -2.041459083557129e-06
pos_z: 0.4424999952316284
q_x: 0
q_y: 0
q_z: 0.04361940470594575
q_w: 0.9990482208247503
rpy: 0.000000 -0.000000 0.087266
wings: 7
Robot_arm2:
pos_x: -0.1137403263029958
pos_y: 1.300031983349814
pos_z: 0.4424999952316284
q_x: 0
q_y: 0
q_z: 0.04361949204551854
q_w: 0.9990482170114167
rpy: 0.000000 -0.000000 0.087267
wings: 3
\ No newline at end of file
{ '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_right_panel', 'pos': { 'x': -0.763760, 'y': 1.243161 , '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': '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
Robot_arm1:
pos_x: -2.041459083557129e-06
pos_y: -0.1000020429491997
pos_z: 0.4424999952316284
q_x: 0
q_y: 0
q_z: 1.249713353108504e-06
q_w: 0.9999999999992193
rpy: 0.000000 -0.000000 0.000002
wings: 7
Robot_arm2:
pos_x: -6.040541873092198e-06
pos_y: 1.499997980887662
pos_z: 0.4424999952316284
q_x: 0
q_y: 0
q_z: 1.337136133234621e-06
q_w: 0.9999999999991062
rpy: 0.000000 -0.000000 0.000003
wings: 7
\ No newline at end of file
{ '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
Robot_arm1:
pos_x: -2.041459083557129e-06
pos_y: -0.1000020429491997
pos_z: 0.4424999952316284
q_x: 0
q_y: 0
q_z: 1.249713353108504e-06
q_w: 0.9999999999992193
rpy: 0.000000 -0.000000 0.000002
wings: 7
Robot_arm2:
pos_x: -6.040541873092198e-06
pos_y: 1.499997980887662
pos_z: 0.4424999952316284
q_x: 0
q_y: 0
q_z: 1.337136133234621e-06
q_w: 0.9999999999991062
rpy: 0.000000 -0.000000 0.000003
wings: 5
\ No newline at end of file
Robot_arm1:
pos_x: -2.041459083557129e-06
pos_y: -0.1000020429491997
pos_z: 0.4424999952316284
q_x: 0
q_y: 0
q_z: 1.249713353108504e-06
q_w: 0.9999999999992193
rpy: 0.000000 -0.000000 0.000002
wings: 7
Robot_arm2:
pos_x: -5.303210804067631e-06
pos_y: 1.204997904594638
pos_z: 0.4424999952316284
q_x: 0
q_y: 0
q_z: 1.337136133234621e-06
q_w: 0.9999999999991062
rpy: 0.000000 -0.000000 0.000003
wings: 3
\ No newline at end of file
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment