update robot gripper and current scene

- added bunker with 4 slots and refactored bunker
This commit is contained in:
Ilya Uraev 2025-03-19 16:32:47 +03:00
parent 4160b2f935
commit 9780e44c1e
14 changed files with 239 additions and 146 deletions

View file

@ -6,7 +6,7 @@
<visual name="bunker_visual"> <visual name="bunker_visual">
<geometry> <geometry>
<mesh> <mesh>
<uri>model://bunker/meshes/Bunker_for_labels_60х40.STL</uri> <uri>model://bunker/meshes/Bunker_50mm_height_for_labels_60х40.STL</uri>
</mesh> </mesh>
</geometry> </geometry>
<material> <material>
@ -14,12 +14,16 @@
<ambient>1 1 1 1</ambient> <ambient>1 1 1 1</ambient>
<specular>0.5 0.5 0.5 1</specular> <specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 1</emissive> <emissive>0 0 0 1</emissive>
<!-- <texture> -->
<!-- <diffuse_map>model://shildik/textures/shildik_sh.png</diffuse_map> -->
<!-- </texture> -->
</material> </material>
</visual> </visual>
<collision name="bunker_collision"> <collision name="bunker_collision">
<geometry> <geometry>
<mesh> <mesh>
<uri>model://bunker/meshes/Bunker_for_labels_60х40.STL</uri> <uri>model://bunker/meshes/Bunker_50mm_height_for_labels_60х40.STL</uri>
</mesh> </mesh>
</geometry> </geometry>
<surface> <surface>

View file

@ -0,0 +1,16 @@
<?xml version="1.0"?>
<model>
<name>bunker_4_slots</name>
<version>0.1</version>
<sdf version='1.10'>model.sdf</sdf>
<author>
<name>Bill Finger</name>
<email>ur.narmak@gmail.com</email>
</author>
<description>
Empty
</description>
</model>

View file

@ -0,0 +1,53 @@
<?xml version="1.0"?>
<sdf version="1.10">
<model name="bunker_4_slots">
<link name="bunker_4_slots_link">
<inertial auto="true" />
<visual name="bunker_4_slots_visual">
<geometry>
<mesh>
<uri>model://bunker_4_slots/meshes/Bunker_50mm_height_for_labels_60х40_4.STL</uri>
</mesh>
</geometry>
<material>
<diffuse>1 1 1 1</diffuse>
<ambient>1 1 1 1</ambient>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 1</emissive>
<!-- <texture> -->
<!-- <diffuse_map>model://shildik/textures/shildik_sh.png</diffuse_map> -->
<!-- </texture> -->
</material>
</visual>
<collision name="bunker_4_slots_collision">
<geometry>
<mesh>
<uri>model://bunker_4_slots/meshes/Bunker_50mm_height_for_labels_60х40_4.STL</uri>
</mesh>
</geometry>
<surface>
<contact>
<ode>
<kp>1e6</kp>
<kd>1e3</kd>
<max_vel>0.1</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
<bounce>
<restitution>0.3</restitution>
</bounce>
<friction>
<ode>
<mu>0.61</mu>
<mu2>0.47</mu2>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
</link>
</model>
</sdf>

Binary file not shown.

Binary file not shown.

Binary file not shown.

View file

@ -1,3 +1,5 @@
#include "geometry_msgs/msg/pose.hpp"
#include "moveit_msgs/msg/collision_object.hpp"
#include "moveit_msgs/msg/planning_scene.hpp" #include "moveit_msgs/msg/planning_scene.hpp"
#include "shape_msgs/msg/mesh.hpp" #include "shape_msgs/msg/mesh.hpp"
#include <chrono> #include <chrono>
@ -11,6 +13,7 @@
#include <shape_msgs/msg/solid_primitive.hpp> #include <shape_msgs/msg/solid_primitive.hpp>
#include <shape_msgs/msg/mesh.hpp> #include <shape_msgs/msg/mesh.hpp>
#include <geometric_shapes/shape_operations.h> #include <geometric_shapes/shape_operations.h>
#include <stdexcept>
class PlanningScenePublisher : public rclcpp::Node { class PlanningScenePublisher : public rclcpp::Node {
public: public:
@ -30,7 +33,7 @@ private:
void publish_scene() { void publish_scene() {
if (object_published_) { if (object_published_) {
return; // Избегаем повторной публикации объекта return;
} }
moveit_msgs::msg::PlanningScene planning_scene; moveit_msgs::msg::PlanningScene planning_scene;
@ -39,12 +42,10 @@ private:
collision_object.header.frame_id = "world"; collision_object.header.frame_id = "world";
collision_object.id = "table"; collision_object.id = "table";
// Определяем геометрию объекта (стола)
shape_msgs::msg::SolidPrimitive table; shape_msgs::msg::SolidPrimitive table;
table.type = shape_msgs::msg::SolidPrimitive::BOX; table.type = shape_msgs::msg::SolidPrimitive::BOX;
table.dimensions = {1.2, 0.7, 0.8}; // Длина, ширина, высота table.dimensions = {1.2, 0.7, 0.8};
// Задаем позу объекта
geometry_msgs::msg::Pose table_pose; geometry_msgs::msg::Pose table_pose;
table_pose.position.x = 0.0; table_pose.position.x = 0.0;
table_pose.position.y = 0.0; table_pose.position.y = 0.0;
@ -56,50 +57,63 @@ private:
planning_scene.world.collision_objects.push_back(collision_object); planning_scene.world.collision_objects.push_back(collision_object);
// Добавляем объект меша
moveit_msgs::msg::CollisionObject mesh_object; moveit_msgs::msg::CollisionObject mesh_object;
mesh_object.header.frame_id = "world"; mesh_object.header.frame_id = "world";
mesh_object.id = "mesh_object"; mesh_object.id = "mesh_object";
shape_msgs::msg::Mesh mesh; std::vector<std::string> meshes = {
shapes::Mesh* m = shapes::createMeshFromResource("package://rbs_mill_assist/assets/laser/meshes/laser.dae"); "package://rbs_mill_assist/assets/laser/meshes/laser.dae",
shapes::ShapeMsg mesh_msg; "package://rbs_mill_assist/assets/bunker/meshes/Bunker_50mm_height_for_labels_60х40.STL",
shapes::constructMsgFromShape(m, mesh_msg); "package://rbs_mill_assist/assets/bunker_4_slots/meshes/Bunker_50mm_height_for_labels_60х40_4.STL"
mesh = boost::get<shape_msgs::msg::Mesh>(mesh_msg); };
//0.30 0.0 0 0 0 3.14159 std::vector<std::vector<double>> mesh_poses = {
geometry_msgs::msg::Pose mesh_pose; {0.350, -0.170, 0.0, 0.0, 0.0, 1.0, 0.0},
mesh_pose.position.x = 0.30; {-0.050, 0.250, 0.0, 0.0, 0.0, 0.707, 0.707},
mesh_pose.position.y = 0.0; {-0.470, 0.250, 0.0, 0.0, 0.0, 0.707, 0.707},
mesh_pose.position.z = 0.0; };
mesh_pose.orientation.x = 0.0; for (size_t i=0; i < meshes.size(); i++) {
mesh_pose.orientation.y = 0.0; auto mesh = getMeshCollisionObject(meshes[i]);
mesh_pose.orientation.z = 1.0; auto mesh_pose = arrayToPose(mesh_poses[i]);
mesh_pose.orientation.w = 0.0; mesh_object.meshes.push_back(mesh);
mesh_object.mesh_poses.push_back(mesh_pose);
}
moveit_msgs::msg::ObjectColor color;
color.id = mesh_object.id;
color.color.r = 0.0;
color.color.g = 1.0;
color.color.b = 0.0;
color.color.a = 1.0;
mesh_object.meshes.push_back(mesh);
mesh_object.mesh_poses.push_back(mesh_pose);
mesh_object.operation = moveit_msgs::msg::CollisionObject::ADD; mesh_object.operation = moveit_msgs::msg::CollisionObject::ADD;
// planning_scene.object_colors.push_back(color);
// planning_scene.object_colors.clear();
planning_scene.world.collision_objects.push_back(mesh_object); planning_scene.world.collision_objects.push_back(mesh_object);
planning_scene.is_diff = true; planning_scene.is_diff = true;
planning_scene_publisher_->publish(planning_scene); planning_scene_publisher_->publish(planning_scene);
RCLCPP_INFO(this->get_logger(), "Published collision objects: table and mesh"); RCLCPP_INFO(this->get_logger(), "Published collision objects: table and mesh");
object_published_ = true; // Устанавливаем флаг, чтобы больше не публиковать объект object_published_ = true;
}
shape_msgs::msg::Mesh getMeshCollisionObject(const std::string &mesh_filepath) {
shape_msgs::msg::Mesh mesh;
shapes::Mesh* m = shapes::createMeshFromResource(mesh_filepath);
shapes::ShapeMsg mesh_msg;
shapes::constructMsgFromShape(m, mesh_msg);
mesh = boost::get<shape_msgs::msg::Mesh>(mesh_msg);
return mesh;
}
geometry_msgs::msg::Pose arrayToPose(const std::vector<double> arr) {
if (arr.size() != 7) {
throw std::invalid_argument("Size of array must be equal 7");
}
geometry_msgs::msg::Pose pose;
pose.position.x = arr[0];
pose.position.y = arr[1];
pose.position.z = arr[2];
pose.orientation.x = arr[3];
pose.orientation.y = arr[4];
pose.orientation.z = arr[5];
pose.orientation.w = arr[6];
return pose;
} }
}; };

View file

@ -7,7 +7,7 @@
<xacro:arg name="namespace" default="arm0"/> <xacro:arg name="namespace" default="arm0"/>
<xacro:arg name="x" default="-0.20" /> <xacro:arg name="x" default="-0.20" />
<xacro:arg name="y" default="0.0" /> <xacro:arg name="y" default="-0.130" />
<xacro:arg name="z" default="0.0" /> <xacro:arg name="z" default="0.0" />
<xacro:arg name="roll" default="0.0" /> <xacro:arg name="roll" default="0.0" />

View file

@ -342,51 +342,51 @@
velocity="10" /> velocity="10" />
</joint> </joint>
<link <link
name="Link6"> name="Link6">
<inertial> <inertial>
<origin <origin
xyz="1.11237115621161E-06 0.105319882001022 0.0151262038950002" xyz="1.11237115621161E-06 0.105319882001022 0.0151262038950002"
rpy="0 0 0" /> rpy="0 0 0" />
<mass <mass
value="0.280654829111196" /> value="0.280654829111196" />
<inertia <inertia
ixx="0.00166005184865464" ixx="0.00166005184865464"
ixy="-2.80959481690827E-08" ixy="-2.80959481690827E-08"
ixz="-7.84445697318557E-10" ixz="-7.84445697318557E-10"
iyy="2.87495064989592E-05" iyy="2.87495064989592E-05"
iyz="-7.18334236975057E-05" iyz="-7.18334236975057E-05"
izz="0.00166929050771312" /> izz="0.00166929050771312" />
</inertial> </inertial>
<visual> <visual>
<origin <origin
xyz="0 0 0" xyz="0 0 0"
rpy="0 0 0" /> rpy="0 0 0" />
<geometry> <geometry>
<mesh <mesh
filename="file://$(find rbs_mill_assist)/meshes/Link6.STL" /> filename="file://$(find rbs_mill_assist)/meshes/Link6.STL" />
</geometry> </geometry>
<material <material
name=""> name="">
<color <color
rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" /> rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
</material> </material>
</visual> </visual>
<collision> <collision>
<origin <origin
xyz="0 0 0" xyz="0 0 0"
rpy="0 0 0" /> rpy="0 0 0" />
<geometry> <geometry>
<mesh <mesh
filename="file://$(find rbs_mill_assist)/meshes/Link6.STL" /> filename="file://$(find rbs_mill_assist)/meshes/Link6.STL" />
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint <joint
name="ax6" name="ax6"
type="revolute"> type="revolute">
<origin <origin
xyz="0.0012 0 0.10155" xyz="0.0012 0 0.10155"
rpy="0 0 0" /> rpy="0 0 3.14" />
<parent <parent
link="Link5" /> link="Link5" />
<child <child
@ -403,17 +403,17 @@
name="Link7"> name="Link7">
<inertial> <inertial>
<origin <origin
xyz="8.67361737988404E-18 0 -0.0036061383699445" xyz="-1.01394587170844E-15 -5.55111512312578E-17 -0.0049950359465929"
rpy="0 0 0" /> rpy="0 0 0" />
<mass <mass
value="0.0198935071603267" /> value="0.0119295697834755" />
<inertia <inertia
ixx="1.01905343575873E-06" ixx="4.27745590342647E-07"
ixy="1.40555551021685E-36" ixy="2.68928440312099E-33"
ixz="-7.39766847562968E-22" ixz="1.44687693702654E-21"
iyy="1.01905343575873E-06" iyy="4.2774559034265E-07"
iyz="-2.63361925044231E-22" iyz="3.0329437472821E-21"
izz="1.43041044988815E-06" /> izz="3.81314853129931E-07" />
</inertial> </inertial>
<visual> <visual>
<origin <origin
@ -443,7 +443,7 @@
name="Right_point" name="Right_point"
type="fixed"> type="fixed">
<origin <origin
xyz="0.015 0.195 0.05" xyz="0 -0.19 0.04"
rpy="0 0 0" /> rpy="0 0 0" />
<parent <parent
link="Link6" /> link="Link6" />
@ -453,64 +453,64 @@
xyz="0 0 0" /> xyz="0 0 0" />
</joint> </joint>
<link <link
name="Link8"> name="Link8">
<inertial> <inertial>
<origin
xyz="-6.10622663543836E-16 -1.11022302462516E-16 -0.0049950359465929"
rpy="0 0 0" />
<mass
value="0.0119295697834755" />
<inertia
ixx="4.2774559034265E-07"
ixy="-2.75001183405761E-33"
ixz="3.1360121197781E-21"
iyy="4.27745590342647E-07"
iyz="-5.45683760877208E-22"
izz="3.81314853129931E-07" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="file://$(find rbs_mill_assist)/meshes/Link8.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 0.4" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="file://$(find rbs_mill_assist)/meshes/Link8.STL" />
</geometry>
</collision>
</link>
<joint
name="Left_point"
type="fixed">
<origin <origin
xyz="1.04083408558608E-17 0 -0.0036061383699445" xyz="0 -0.164999999999954 0.0399999999999993"
rpy="0 0 0" /> rpy="0 0 0" />
<mass <parent
value="0.0198935071603267" /> link="Link6" />
<inertia <child
ixx="1.01905343575873E-06" link="Link8" />
ixy="1.10608362843633E-36" <axis
ixz="-7.54785908468325E-22" xyz="0 0 0" />
iyy="1.01905343575873E-06" </joint>
iyz="-2.63361925044231E-22"
izz="1.43041044988815E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="file://$(find rbs_mill_assist)/meshes/Link8.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 0.4" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="file://$(find rbs_mill_assist)/meshes/Link8.STL" />
</geometry>
</collision>
</link>
<joint
name="Left_point"
type="fixed">
<origin
xyz="-0.015 0.195 0.05"
rpy="0 0 0" />
<parent
link="Link6" />
<child
link="Link8" />
<axis
xyz="0 0 0" />
</joint>
<link name="grasp_point" /> <link name="grasp_point" />
<joint <joint
name="grasp_point_joint" name="grasp_point_joint"
type="fixed"> type="fixed">
<origin <origin
xyz="0.0 0.195 0.05" xyz="0.0 -0.177 0.04"
rpy="0 0 0" /> rpy="0 0 0" />
<parent <parent
link="Link6" /> link="Link6" />
@ -611,7 +611,7 @@
<xacro:gazebo_reference joint_name="left_contact_panel_joint" /> <xacro:gazebo_reference joint_name="left_contact_panel_joint" />
<xacro:joint_hardware joint_name="ax1" hardware="${hardware}" initial_joint_position="0.0" /> <xacro:joint_hardware joint_name="ax1" hardware="${hardware}" initial_joint_position="3.14" />
<xacro:joint_hardware joint_name="ax2" hardware="${hardware}" initial_joint_position="0.85" /> <xacro:joint_hardware joint_name="ax2" hardware="${hardware}" initial_joint_position="0.85" />
<xacro:joint_hardware joint_name="ax3" hardware="${hardware}" initial_joint_position="1.0" /> <xacro:joint_hardware joint_name="ax3" hardware="${hardware}" initial_joint_position="1.0" />
<xacro:joint_hardware joint_name="ax4" hardware="${hardware}" initial_joint_position="0.0" /> <xacro:joint_hardware joint_name="ax4" hardware="${hardware}" initial_joint_position="0.0" />

View file

@ -41,7 +41,7 @@
</plugin> </plugin>
<light type="directional" name="sun"> <light type="directional" name="sun">
<cast_shadows>true</cast_shadows> <cast_shadows>false</cast_shadows>
<pose>0 0 10 0 0 0</pose> <pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse> <diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular> <specular>0.2 0.2 0.2 1</specular>
@ -56,45 +56,51 @@
<include> <include>
<name>shildik_0</name> <name>shildik_0</name>
<pose>-0.5 -0.2 0.02 0 0 1.57</pose> <pose>-0.403959 0.250 0.02 0 0 1.57</pose>
<uri>model://shildik</uri> <uri>model://shildik</uri>
</include> </include>
<include> <include>
<name>shildik_1</name> <name>shildik_1</name>
<pose>-0.5 -0.2 0.04 0 0 1.57</pose> <pose>-0.447918 0.250 0.02 0 0 1.57</pose>
<uri>model://shildik</uri> <uri>model://shildik</uri>
</include> </include>
<include> <include>
<name>shildik_2</name> <name>shildik_2</name>
<pose>-0.5 -0.2 0.05 0 0 1.57</pose> <pose>-0.491997 0.250 0.02 0 0 1.57</pose>
<uri>model://shildik</uri> <uri>model://shildik</uri>
</include> </include>
<include> <include>
<name>shildik_3</name> <name>shildik_3</name>
<pose>-0.5 -0.2 0.06 0 0 1.57</pose> <pose>-0.536033 0.250 0.02 0 0 1.57</pose>
<uri>model://shildik</uri> <uri>model://shildik</uri>
</include> </include>
<include> <include>
<name>shildik_4</name> <name>shildik_4</name>
<pose>-0.5 -0.2 0.07 0 0 1.57</pose> <pose>-0.491997 0.250 0.03 0 0 1.57</pose>
<uri>model://shildik</uri> <uri>model://shildik</uri>
</include> </include>
<include> <include>
<static>true</static> <static>true</static>
<pose>0.30 0.0 0 0 0 3.14159</pose> <pose>0.350 -0.170 0 0 0 3.14159</pose>
<uri>model://laser</uri> <uri>model://laser</uri>
</include> </include>
<include> <include>
<static>true</static> <static>true</static>
<pose>-0.505 -0.20 0.06 0.0 0.0 1.57</pose> <pose>-0.050 0.250 0.0 0.0 0.0 1.57</pose>
<uri>model://bunker</uri> <uri>model://bunker</uri>
</include> </include>
<include> <include>
<static>true</static> <static>true</static>
<pose>0.20 0 0.01 0 0 1.57</pose> <pose>-0.470 0.250 0 0 0 1.57</pose>
<uri>model://bunker_4_slots</uri>
</include>
<include>
<static>true</static>
<pose>0.350 -0.170 0.01 0 0 1.57</pose>
<uri>model://conductor</uri> <uri>model://conductor</uri>
</include> </include>