当前位置:网站首页>Moveit 避障路径规划 demo
Moveit 避障路径规划 demo
2022-07-02 12:20:00 【陈君豪】
#include <moveit/move_group_interface/move_group_interface.h>
#include <moveit/planning_scene_interface/planning_scene_interface.h>
#include <moveit_msgs/CollisionObject.h>
int main(int argc, char **argv)
{
ros::init(argc, argv, "full_demo");
ros::NodeHandle nh;
ros::AsyncSpinner spin(1);
spin.start();
// 创建运动规划的情景,等待创建完成
ros::Publisher planning_scene_diff_publisher = nh.advertise<moveit_msgs::PlanningScene>("planning_scene", 1);
ros::WallDuration sleep_t(0.5);
while (planning_scene_diff_publisher.getNumSubscribers() < 1)
{
sleep_t.sleep();
}
moveit::planning_interface::MoveGroupInterface arm("arm");
//无障碍的动作
std::vector<double> joints={0.7,-1.57,0,0,0};
arm.setJointValueTarget(joints);
moveit::planning_interface::MoveGroupInterface::Plan my_plan;
moveit::planning_interface::MoveItErrorCode success = arm.plan(my_plan);
if(success) {
arm.execute(my_plan);
}
joints={-0.7,-1.57,0,0,0};
arm.setJointValueTarget(joints);
success = arm.plan(my_plan);
if(success) {
arm.execute(my_plan);
}
moveit_msgs::PlanningScene planning_scene;
std::string id_1="1";
std::string id_2="2";
// // 第一个障碍物
moveit_msgs::CollisionObject cylinder;
cylinder.header.frame_id = "base_link";
cylinder.id=id_1;
//定义物体形状尺寸
shape_msgs::SolidPrimitive primitive;
primitive.type=primitive.CYLINDER;
primitive.dimensions.resize(3); //dimensions是一个vector,为其分配3个元素空间
primitive.dimensions[0] =0.6; //圆柱体高度
primitive.dimensions[1] =0.05; //半径
geometry_msgs::Pose pose;
pose.orientation.w =1.0;
pose.position.x=0;
pose.position.y=0.2;
pose.position.z=0;
cylinder.primitives.push_back(primitive);
cylinder.primitive_poses.push_back(pose);
//定义操作为添加
cylinder.operation = cylinder.ADD;
planning_scene.world.collision_objects.emplace_back(cylinder);
//第二个障碍物
cylinder.header.frame_id = "base_link";
cylinder.id=id_2;
//定义物体形状尺寸
primitive.type=primitive.CYLINDER;
primitive.dimensions.resize(3); //dimensions是一个vector,为其分配3个元素空间
primitive.dimensions[0] =0.3; //圆柱体高度
primitive.dimensions[1] =0.05; //半径
pose.orientation.w =1.0;
pose.position.x=-0.07;
pose.position.y=0.2;
pose.position.z=0;
cylinder.primitives.push_back(primitive);
cylinder.primitive_poses.push_back(pose);
cylinder.operation = cylinder.ADD;
planning_scene.world.collision_objects.emplace_back(cylinder);
//发布
planning_scene.is_diff = true;
planning_scene_diff_publisher.publish(planning_scene);
//避障运动
joints={0.7,-1.57,0,0,0};
arm.setJointValueTarget(joints);
success = arm.plan(my_plan);
if(success) {
arm.execute(my_plan);
}
//移除障碍物
moveit::planning_interface::PlanningSceneInterface current_scene;
std::vector<std::string> object_ids;
object_ids.emplace_back(id_1);
object_ids.emplace_back(id_2);
current_scene.removeCollisionObjects(object_ids);
while (ros::ok()){
}
return 0;
}
边栏推荐
- Summary of the first three passes of sqli Labs
- 党史纪实主题公益数字文创产品正式上线
- 02. After containerization, you must face golang
- 【LeetCode】19-删除链表的倒数第N个结点
- 数字藏品系统开发(程序开发)丨数字藏品3D建模经济模式系统开发源码
- [leetcode] 189 rotation array
- (5) Flink's table API and SQL update mode and Kafka connector case
- Yolo format data set processing (XML to txt)
- SQL stored procedure
- fastjson List转JSONArray以及JSONArray转List「建议收藏」
猜你喜欢
6.12 critical moment of Unified Process Platform
2022 年辽宁省大学生数学建模A、B、C题(相关论文及模型程序代码网盘下载)
【LeetCode】1254-统计封闭岛屿的数量
Deux séquences ergodiques connues pour construire des arbres binaires
Semantic segmentation learning notes (1)
Leetcode skimming -- sum of two integers 371 medium
(Video + graphic) machine learning introduction series - Chapter 5 machine learning practice
5. Practice: jctree implements the annotation processor at compile time
[network security] network asset collection
Storage read-write speed and network measurement based on rz/g2l | ok-g2ld-c development board
随机推荐
matlab中wavedec2,说说wavedec2函数[通俗易懂]
SQL transaction
Loss function and positive and negative sample allocation: Yolo series
Redux - detailed explanation
/bin/ld: 找不到 -lxml2
Bing. Com website
[leetcode] 1254 - count the number of closed Islands
2022 college students in Liaoning Province mathematical modeling a, B, C questions (related papers and model program code online disk download)
[leetcode] 344 reverse string
[leetcode] 1905 statistics sub Island
LeetCode刷题——两整数之和#371#Medium
Jsp+mysql006 community management system
LeetCode刷题——递增的三元子序列#334#Medium
【LeetCode】695-岛屿的最大面积
【LeetCode】344-反转字符串
[salesforce] how to confirm your salesforce version?
College entrance examination score line climbing
2303. 计算应缴税款总额
Two traversal sequences are known to construct binary trees
6092. Replace elements in the array