MTC完成右臂抓取放置任务\\放置姿态设置

news2024/11/13 9:36:21

MT

#include "mtc_tutorial/mtc_glass_bottle.hpp"
static const rclcpp::Logger LOGGER = rclcpp::get_logger("mtc_glass_right"); 

// 获取节点基础接口的实现
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr MTCTaskNode_Right::getNodeBaseInterface()
{
  return node_->get_node_base_interface();
}

// 构造函数的实现,创建节点对象
MTCTaskNode_Right::MTCTaskNode_Right(const rclcpp::NodeOptions& options)
  : node_{ std::make_shared<rclcpp::Node>("mtc_right_node", options) }  // 初始化节点名称为 "mtc_node"
{
}

// 设置规划场景的实现
void MTCTaskNode_Right::setupPlanningScene()
{
  const double table_height = 1.02;
  std::string frame_id = "world";

  geometry_msgs::msg::PoseStamped bottlePose;
  bottlePose.header.frame_id = frame_id;
  bottlePose.pose.position.x = 0.3;
  bottlePose.pose.position.y = -0.5;
  bottlePose.pose.position.z = table_height;
  bottlePose.pose.orientation.w = 1.0;

  geometry_msgs::msg::PoseStamped glassPose;
  glassPose.header.frame_id = frame_id;
  glassPose.pose.position.x = -0.6;
  glassPose.pose.position.y = -0.5;
  glassPose.pose.position.z = table_height;
  glassPose.pose.orientation.w = 1.0;

  // center of table surface 
  geometry_msgs::msg::PoseStamped tabletopPose;
  tabletopPose.header.frame_id = frame_id;
  tabletopPose.pose.position.x = 0;
  tabletopPose.pose.position.y = -0.25;
  tabletopPose.pose.position.z = table_height;
  tabletopPose.pose.orientation.w = 1.0;
  

  // 创建规划场景接口并将碰撞对象添加到场景中
  mtc_pour::cleanup();
  moveit::planning_interface::PlanningSceneInterface psi;
  std::vector<moveit_msgs::msg::CollisionObject> objs;
  mtc_pour::setupTable(objs, tabletopPose);
  mtc_pour::setupObjects(objs, bottlePose, glassPose,
                          "package://mtc_pour/meshes/small_bottle.stl");
  psi.applyCollisionObjects(objs);
}

// 执行任务的实现
void MTCTaskNode_Right::doTask()
{
  task_ = createTask();  // 创建任务

  // 尝试初始化任务
  try
  {
    task_.init();  // 初始化任务
  }
  catch (mtc::InitStageException& e)  // 捕获初始化失败的异常
  {
    RCLCPP_ERROR_STREAM(LOGGER, e);  // 打印错误信息
    return;
  }

  // 规划任务路径,最大规划尝试次数为 5
  if (!task_.plan(10))
  {
    RCLCPP_ERROR_STREAM(LOGGER, "Task planning failed");  // 打印任务规划失败的日志
    return;
  }
  
  // 发布任务解决方案以供检查
  task_.introspection().publishSolution(*task_.solutions().front());

  // 执行规划的解决方案
  auto result = task_.execute(*task_.solutions().front());
  if (result.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
  {
    RCLCPP_ERROR_STREAM(LOGGER, "Task execution failed");  // 执行失败的错误日志
    return;
  }

  return;
}

// 创建任务的实现
mtc::Task MTCTaskNode_Right::createTask()
{
  mtc::Task task;  // 创建一个 MTC 任务对象
  task.stages()->setName("grabbing the glass on the right");  // 为任务命名
  task.loadRobotModel(node_);  // 加载机器人模型

  // 定义机器人操作相关的参数
  // const auto& left_arm_group_name = "left_ur_manipulator";  // 机械臂的操作组名称
  // const auto& left_hand_group_name = "left_robotiq_2f_85_gripper";  // 手部操作组名称
  // const auto& left_hand_frame = "left_robotiq_85_base_link";  // 机械手的坐标系

  const auto& right_arm_group_name = "right_ur_manipulator";  // 机械臂的操作组名称
  const auto& right_hand_group_name = "right_robotiq_2f_85_gripper";  // 手部操作组名称
  const auto& right_hand_frame = "right_grasp_point";  // 机械手的坐标系

  // 设置任务的属性
  task.setProperty("group", right_arm_group_name);
  task.setProperty("eef", "right_robotiq_2f_85_gripper_ee");
  task.setProperty("ik_frame", right_hand_frame);

  // 忽略未使用变量的编译器警告
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-but-set-variable"
  mtc::Stage* current_state_ptr = nullptr;  // 将current_stage传递给grasp pose generator
#pragma GCC diagnostic pop

  // 创建并添加获取当前状态的阶段
  auto stage_state_current = std::make_unique<mtc::stages::CurrentState>("right-current");
  current_state_ptr = stage_state_current.get();
  task.add(std::move(stage_state_current));  // 添加当前状态阶段到任务中

  // 创建不同的规划器
  auto sampling_planner = std::make_shared<mtc::solvers::PipelinePlanner>(node_);  // 创建采样规划器
  auto interpolation_planner = std::make_shared<mtc::solvers::JointInterpolationPlanner>();  // 创建插值规划器

  // 创建笛卡尔路径规划器,并设置最大速度和加速度
  auto cartesian_planner = std::make_shared<mtc::solvers::CartesianPath>();
  cartesian_planner->setMaxVelocityScalingFactor(1.0);  // 设置最大速度缩放因子为 1.0
  cartesian_planner->setMaxAccelerationScalingFactor(1.0);  // 设置最大加速度缩放因子为 1.0
  cartesian_planner->setStepSize(.01);  // 设置步长为 0.01

  // 创建并添加手部动作的阶段(打开手)
  auto stage_open_right_hand =
      std::make_unique<mtc::stages::MoveTo>("open right_hand", interpolation_planner);  // 创建移动到目标状态的阶段
  stage_open_right_hand->setGroup(right_hand_group_name);  // 设置操作组为手部
  stage_open_right_hand->setGoal("right_open");  // 设置手部打开的目标状态
  task.add(std::move(stage_open_right_hand));  // 将阶段添加到任务中
  
  // Add the next lines of codes to define more stages here
  auto stage_move_to_pick_right = std::make_unique<mtc::stages::Connect>(
    "move to pick-right",
    mtc::stages::Connect::GroupPlannerVector{{right_arm_group_name,sampling_planner}});
  stage_move_to_pick_right->setTimeout(5.0);
  stage_move_to_pick_right->properties().configureInitFrom(mtc::Stage::PARENT);
  task.add(std::move(stage_move_to_pick_right));

  mtc::Stage* attach_object_stage_right = nullptr;// Forward attach_object_stage  to place pose generator
  {
    auto grasp_right = std::make_unique<mtc::SerialContainer>("pick glass-right");
    task.properties().exposeTo(grasp_right->properties(),{"eef","group","ik_frame"});
    grasp_right->properties().configureInitFrom(mtc::Stage::PARENT,{"eef","group","ik_frame"});

    {
      auto stage = std::make_unique<mtc::stages::MoveRelative>("approach glass-right",cartesian_planner);
      stage->properties().set("marker_ns","approach_glass-right");
      stage->properties().set("link",right_hand_frame);// TODO:猜测这是与物体发生接触的link
      stage->properties().configureInitFrom(mtc::Stage::PARENT,{"group"});
      stage->setMinMaxDistance(0.05,0.15);
      // Set hand forward direction
      geometry_msgs::msg::Vector3Stamped vec;
      vec.header.frame_id = right_hand_frame;
      vec.vector.z =1.0;
      stage->setDirection(vec);
      grasp_right->insert(std::move(stage));
    }

    {
      //Sample grasp pose
      auto stage = std::make_unique<mtc::stages::GenerateGraspPose>("generate grasp pose -right");
      stage->properties().configureInitFrom(mtc::Stage::PARENT);
      stage->properties().set("marker_ns","grasp_pose-right");
      stage->setPreGraspPose("right_open");
      stage->setObject("glass");
      stage->setAngleDelta(M_PI / 12);
      stage->setMonitoredStage(current_state_ptr);//Hook into current state

      Eigen::Isometry3d grasp_frame_transform_right;
      
      //末端执行器坐标系的Z轴朝向杯子的X轴,末端执行器坐标系的X轴朝向杯子的Y轴,末端执行器坐标系的Y轴朝向杯子的Z轴
      Eigen::Quaterniond q = Eigen:: AngleAxisd(-M_PI/2,Eigen::Vector3d::UnitY())*
                            Eigen::AngleAxisd(-M_PI/2,Eigen::Vector3d::UnitX());
      
      // //末端执行器坐标系的Y轴朝向杯子的X轴,末端执行器坐标系的X轴朝向杯子的Y轴,末端执行器坐标系的Z轴朝向杯子的-Z轴
      // Eigen::Quaterniond q = Eigen:: AngleAxisd(M_PI/2,Eigen::Vector3d::UnitZ())*
      //                       Eigen::AngleAxisd(-M_PI,Eigen::Vector3d::UnitX());

      grasp_frame_transform_right.linear() = q.matrix();
      grasp_frame_transform_right.translation().z()=0;


      // Compute IK
      // 将stage对象的所有权转移给wrapper_right
      // wrapper 通常指的是一层封装,用于将某个功能或一组功能封装起来,
      auto wrapper = std::make_unique<mtc::stages::ComputeIK>("grasp pose IK - right",std::move(stage));
      wrapper->setMaxIKSolutions(8);
      wrapper->setMinSolutionDistance(1.0);
      wrapper->setIKFrame(grasp_frame_transform_right,right_hand_frame);
      wrapper->properties().configureInitFrom(mtc::Stage::PARENT,{"eef","group"});
      wrapper->properties().configureInitFrom(mtc::Stage::INTERFACE,{"target_pose"});
      grasp_right->insert(std::move(wrapper));
    }

    {
      auto stage = 
          std::make_unique<mtc::stages::ModifyPlanningScene>("allow collision (hand,object) - right");
      stage->allowCollisions("glass",
                              task.getRobotModel()
                              ->getJointModelGroup(right_hand_group_name)
                              ->getLinkModelNamesWithCollisionGeometry(),
                              true);
      grasp_right->insert(std::move(stage));
    }

    {
      auto stage = std::make_unique<mtc::stages::MoveTo>("close hand-right",interpolation_planner);
      stage->setGroup(right_hand_group_name);
      stage->setGoal("right_close");
      grasp_right->insert(std::move(stage));
    }

    {
      auto stage = std::make_unique<mtc::stages::ModifyPlanningScene>("attcah object - right");
      stage->attachObject("glass",right_hand_frame);
      attach_object_stage_right = stage.get();
      grasp_right->insert(std::move(stage));
    }

    {
      auto stage = std::make_unique<mtc::stages::MoveRelative>("lift object - right",cartesian_planner);
      stage->properties().configureInitFrom(mtc::Stage::PARENT,{"group"});
      stage->setMinMaxDistance(0.1,0.3);
      stage->setIKFrame(right_hand_frame);
      stage->properties().set("marker_ns","lift_object_right");

      // Set upward direction
      geometry_msgs::msg::Vector3Stamped vec;
      vec.header.frame_id = "dual_base";
      vec.vector.y = 1.0;
      stage->setDirection(vec);
      grasp_right->insert(std::move(stage));
    }

    task.add(std::move(grasp_right));  
  }

  {
    auto stage_move_to_place_right = std::make_unique<mtc::stages::Connect>(
      "move to place -right",
      mtc::stages::Connect::GroupPlannerVector{{right_arm_group_name,sampling_planner},
                                              {right_hand_group_name,sampling_planner} });
    stage_move_to_place_right->setTimeout(5.0);
    stage_move_to_place_right->properties().configureInitFrom(mtc::Stage::PARENT);
    task.add(std::move(stage_move_to_place_right));
  }

  {
    auto place_right = std::make_unique<mtc::SerialContainer>("place object -right");
    task.properties().exposeTo(place_right->properties(),{"eef","group","ik_frame"});
    place_right->properties().configureInitFrom(mtc::Stage::PARENT,
                                              {"eef","group","ik_frame"});

    // {
    //   //Sample place pose
    //   auto stage = std::make_unique<mtc::stages::GeneratePlacePose>("generate place pose");
    //   stage->properties().configureInitFrom(mtc::Stage::PARENT);
    //   stage->properties().set("marker_ns","place_pose_right");
    //   stage->setObject("glass");

    //   geometry_msgs::msg::PoseStamped target_pose_msg_right;
    //   target_pose_msg_right.header.frame_id = "dual_base";
    //   target_pose_msg_right.pose.position.x = -0.5;
    //   target_pose_msg_right.pose.position.y = -0.5;
    //   target_pose_msg_right.pose.position.z = 0.55;
    //   tf2::Quaternion qtn;
    //   qtn.setRPY(0.0,0.0,-1.57);
    //   target_pose_msg_right.pose.orientation.x = qtn.x();
    //   target_pose_msg_right.pose.orientation.y = qtn.y();
    //   target_pose_msg_right.pose.orientation.z = qtn.z();
    //   target_pose_msg_right.pose.orientation.w = qtn.w();
    //   stage->setPose(target_pose_msg_right);
    //   stage->setMonitoredStage(attach_object_stage_right); //Hook into attach_object_stage

    //   // Compute IK
    //   auto wrapper = std::make_unique<mtc::stages::ComputeIK>("place pose IK",std::move(stage));
    //   wrapper->setMaxIKSolutions(2);
    //   wrapper->setMinSolutionDistance(1.0);
    //   wrapper->setIKFrame("glass");
    //   wrapper->properties().configureInitFrom(mtc::Stage::PARENT,{"eef","group"});
    //   wrapper->properties().configureInitFrom(mtc::Stage::INTERFACE,{"target_pose"});
    //   place_right->insert(std::move(wrapper));

    //  }

    //  {
    //     //Sample place pose
    //     auto stage = std::make_unique<mtc::stages::GeneratePlacePose>("generate place pose -right");
    //     stage->properties().configureInitFrom(mtc::Stage::PARENT);
    //     stage->properties().set("marker_ns","place_pose_right");
    //     stage->setObject("glass");

    //     // 定义放置位姿
    //     geometry_msgs::msg::PoseStamped target_pose_msg_right;
    //     target_pose_msg_right.header.frame_id = "dual_base";
    //     target_pose_msg_right.pose.position.x = -0.5;
    //     target_pose_msg_right.pose.position.y = 0.5;
    //     target_pose_msg_right.pose.position.z = 0.2;
    //     tf2::Quaternion qtn;
    //     qtn.setRPY(0.0, 0.0, -M_PI );  // 将RPY角度转换成四元数
    //     target_pose_msg_right.pose.orientation.x = qtn.x();
    //     target_pose_msg_right.pose.orientation.y = qtn.y();
    //     target_pose_msg_right.pose.orientation.z = qtn.z();
    //     target_pose_msg_right.pose.orientation.w = qtn.w();
    //     stage->setPose(target_pose_msg_right);

    //     stage->setMonitoredStage(attach_object_stage_right); //Hook into attach_object_stage

    //     // 定义放置时的末端执行器坐标系变换
    //     Eigen::Isometry3d place_frame_transform_right;
    //     Eigen::Quaterniond q = Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY()) *
    //                           Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitX());
    //     place_frame_transform_right.linear() = q.matrix();
    //     place_frame_transform_right.translation().z() = 0;

    //     // 计算IK
    //     auto wrapper = std::make_unique<mtc::stages::ComputeIK>("place pose IK - right", std::move(stage));
    //     wrapper->setMaxIKSolutions(8); // 设置最大解的数量
    //     wrapper->setMinSolutionDistance(1.0);
    //     wrapper->setIKFrame(place_frame_transform_right, right_hand_frame);
    //     wrapper->properties().configureInitFrom(mtc::Stage::PARENT, {"eef", "group"});
    //     wrapper->properties().configureInitFrom(mtc::Stage::INTERFACE, {"target_pose"});
    //     place_right->insert(std::move(wrapper));
    // }

      {
      // Sample place pose
      auto stage = std::make_unique<mtc::stages::GeneratePlacePose>("generate place pose -right");
      stage->properties().configureInitFrom(mtc::Stage::PARENT);
      stage->properties().set("marker_ns", "place_pose_right");
      stage->setObject("glass");

      // 定义放置位姿
      geometry_msgs::msg::PoseStamped target_pose_msg_right;
      target_pose_msg_right.header.frame_id = "dual_base";
      target_pose_msg_right.pose.position.x = -0.3;
      target_pose_msg_right.pose.position.y = -0.5;
      target_pose_msg_right.pose.position.z = 0.3;

      // 计算放置位姿的正确姿态
      Eigen::Quaterniond q_place = Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitZ())*
                                  Eigen::AngleAxisd(0, Eigen::Vector3d::UnitX());
      Eigen::Quaterniond q_object = q_place.inverse();

      tf2::Quaternion qtn(q_object.x(), q_object.y(), q_object.z(), q_object.w());
      target_pose_msg_right.pose.orientation = tf2::toMsg(qtn);

      stage->setPose(target_pose_msg_right);
      stage->setMonitoredStage(attach_object_stage_right); // Hook into attach_object_stage

      // 设置 IK 框架,与抓取阶段一致
      Eigen::Isometry3d place_frame_transform_right;
      place_frame_transform_right.linear() = q_place.toRotationMatrix();
      place_frame_transform_right.translation().z() = 0;

      // 计算 IK
      auto wrapper = std::make_unique<mtc::stages::ComputeIK>("place pose IK - right", std::move(stage));
      wrapper->setMaxIKSolutions(8); // 设置最大解的数量
      wrapper->setMinSolutionDistance(1.0);
      wrapper->setIKFrame(place_frame_transform_right, right_hand_frame);
      wrapper->properties().configureInitFrom(mtc::Stage::PARENT, { "eef", "group" });
      wrapper->properties().configureInitFrom(mtc::Stage::INTERFACE, { "target_pose" });
      place_right->insert(std::move(wrapper));
  }

    


    {
      auto stage = std::make_unique<mtc::stages::MoveTo>("open hand-right",interpolation_planner);
      stage->setGroup(right_hand_group_name);
      stage->setGoal("right_open");
      place_right->insert(std::move(stage));
    }

    {
    auto stage = std::make_unique<mtc::stages::ModifyPlanningScene>("forbid collision (hand,object)-right");
    stage->allowCollisions("glass",
                            task.getRobotModel()
                                 ->getJointModelGroup(right_hand_group_name)
                                 ->getLinkModelNamesWithCollisionGeometry(),
                                 false);
    place_right->insert(std::move(stage));
    }

    {
      auto stage = std::make_unique<mtc::stages::ModifyPlanningScene>("detach object-right");
      stage->detachObject("glass",right_hand_frame);
      place_right->insert(std::move(stage));
    }

    {
      auto stage = std::make_unique<mtc::stages::MoveRelative>("retreat -right",cartesian_planner);
      stage->properties().configureInitFrom(mtc::Stage::PARENT,{"group"});
      stage->setMinMaxDistance(0.1,0.3);
      stage->setIKFrame(right_hand_frame);
      stage->properties().set("marker_ns","retreat-right");

      // Set retreat direction
      geometry_msgs::msg::Vector3Stamped vec;
      vec.header.frame_id = "world";
      vec.vector.z=0.5;
      stage->setDirection(vec);
      place_right->insert(std::move(stage));
    }

    task.add(std::move(place_right));
  }

  {
    auto stage = std::make_unique<mtc::stages::MoveTo>("return home -right",interpolation_planner);
    stage->properties().configureInitFrom(mtc::Stage::PARENT,{"group"});
    stage->setGoal("right_home");
    task.add(std::move(stage));
  }

  // Stages all added to the task above this line
  return task;  // 返回创建的任务
}



本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.coloradmin.cn/o/2141281.html

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈,一经查实,立即删除!

相关文章

(c++)字符串相加(真没想到字符串还有相加运算)

#include<iostream> #include<string> using namespace std;int main() {string ch1 "你好";string ch2 "再见";string ch3 ch1 ch2;cout << ch3 << endl;system("pause");return 0; } 运行结果&#xff1a; 学了c…

FreeRTOS学习——链表list

FreeRTOS学习——链表&#xff08;列表&#xff09;list&#xff0c;仅用于记录自己阅读与学习源码 FreeRTOS Kernel V10.5.1 参考大佬的好文章&#xff1a; freertos内核原理 Day1(链表) FreeRTOS-链表的源码解析 *list_t只能存储指向list_item_t的指针。每个list_item_t都…

【UE5 C++课程系列笔记】01——Visual Studio环境安装

1. 进入Visual Studio 官网&#xff0c;点击下载 下载社区版即可 下载后点击应用程序开始安装 2. 在“工作负荷”中&#xff0c;勾选如下选项 在“单个组件”中&#xff0c;勾选如下选项&#xff1a; 3. 等待下载安装 4. 安装好后&#xff0c;点击“继续但无需代码” 选择“工具…

《python语言程序设计》2018版第8章17题point类设计一个名为point的类

TypeError: point_class.dis_m() missing 1 required positional argument: ‘y2’ 这段代码为什么出错 一个又一个错误 终于摸到点头绪 #distance方法 我做的叫get_dis_m def get_dis_m(self):a_m self.__x1 - self.__x2b_m self.__y1 - self.__y2return (pow(a_m, 2) po…

k8s中的存储

目录 一 configmap 1.1 configmap的功能 1.2 configmap的使用场景 1.3 configmap创建方式 1.3.1 字面值创建 1.3.2 通过文件创建 1.3.3 通过目录创建 1.3.4 通过yaml文件创建 1.3.5 configmap的使用方式 1.3.5.1 使用configmap填充环境变量 1.3.5.2 通过数据卷使用c…

《程序猿之设计模式实战 · 观察者模式》

&#x1f4e2; 大家好&#xff0c;我是 【战神刘玉栋】&#xff0c;有10多年的研发经验&#xff0c;致力于前后端技术栈的知识沉淀和传播。 &#x1f497; &#x1f33b; CSDN入驻不久&#xff0c;希望大家多多支持&#xff0c;后续会继续提升文章质量&#xff0c;绝不滥竽充数…

AJAX 进阶 day4

目录 1.同步代码和异步代码 2.回调函数地狱和 Promise 链式调用 2.1 回调函数地狱 2.2 Promise - 链式调用 2.3 Promise 链式应用 3.async 和 await 使用 3.1 async函数和await 3.2 async函数和await_捕获错误 4.事件循环-EventLoop 4.1 事件循环 4.2 宏任务与微任务…

R语言统计分析——散点图1(常规图)

参考资料&#xff1a;R语言实战【第2版】 R语言中创建散点图的基础函数是plot(x,y)&#xff0c;其中&#xff0c;x和y是数值型向量&#xff0c;代表着图形中的&#xff08;x,y&#xff09;坐标点。 attach(mtcars) plot(wt,mpg,main"Basic Scatter plot of MPG vs. Weigh…

数据结构(Day14)

一、学习内容 结构体 概念 引入&#xff1a;定义整数赋值为10 int a10; 定义小数赋值为3.14 float b3.14; 定义5个整数并赋值 int arr[5] {1 , 2 , 3 , 4 ,5}; 定义一个学生并赋值学号姓名成绩 定义一个雪糕并赋值名称产地单价 问题&#xff1a;没有学生、雪糕 数据类型 解决&…

Text2vec -文本转向量

文章目录 一、关于 Text2vec1、Text2vec 是什么2、Features3、Demo4、News5、Evaluation英文匹配数据集的评测结果&#xff1a;中文匹配数据集的评测结果&#xff1a; 6、Release Models 二、Install三、使用1、文本向量表征1.2 Usage (HuggingFace Transformers)1.3 Usage (se…

★ C++进阶篇 ★ 多态

Ciallo&#xff5e;(∠・ω< )⌒☆ ~ 今天&#xff0c;我将继续和大家一起学习C进阶篇第一章----多态 ~ ❄️❄️❄️❄️❄️❄️❄️❄️❄️❄️❄️❄️❄️❄️ 澄岚主页&#xff1a;椎名澄嵐-CSDN博客 C基础篇专栏&#xff1a;★ C基础篇 ★_椎名澄嵐的博客-CSDN博客 …

2024/9/16 英语每日一段

Stark argues that, in their gummies, at least,“The total sugar in a serving is less than in half a cherry.”Of course, cherries also provide fibre, vitamin C, and antioxidants--and 14 of them would count as one of your five-a-day. Artificial sweeteners to…

Ubuntu24.04部署docker

1、更新软件 apt update 2、安装curl apt install apt-transport-https curl 3、导入阿里云GPG秘钥 curl -fsSL https://mirrors.aliyun.com/docker-ce/linux/ubuntu/gpg | sudo gpg --dearmor -o /etc/apt/keyrings/docker.gpg 4、添加Docker阿里云仓库到Ubuntu 24.04的…

使用 release key 对 LineageOS 进行编译和签名

版权归作者所有&#xff0c;如有转发&#xff0c;请注明文章出处&#xff1a;https://cyrus-studio.github.io/blog/ 为什么需要使用 release key test-key 是一个公开的、众所周知的开发测试密钥&#xff0c;广泛用于测试阶段。这意味着任何人都可以获取这个密钥&#xff0c;…

详解HTTP/HTTPS协议

HTTP HTTP协议全名为超文本传输协议。HTTP协议是应用层协议&#xff0c;其传输层协议采用TCP协议。 请求—响应模型 HTTP协议采用请求-响应模型&#xff0c;通常由客户端发起请求由服务端完成响应。资源存储在服务端&#xff0c;客户端通过请求服务端获取资源。 认识URL 当…

jacoco生成单元测试覆盖率报告

前言 单元测试是日常编写代码中常用的&#xff0c;用于测试业务逻辑的一种方式&#xff0c;单元测试的覆盖率可以用来衡量我们的业务代码经过测试覆盖的比例。 目前市场上开源的单元测试覆盖率的java插件&#xff0c;主要有Emma&#xff0c;Cobertura&#xff0c;Jacoco。具体…

后台数据管理系统 - 项目架构设计-Vue3+axios+Element-plus(0916)

接口文档: https://apifox.com/apidoc/shared-26c67aee-0233-4d23-aab7-08448fdf95ff/api-93850835 接口根路径&#xff1a; http://big-event-vue-api-t.itheima.net 本项目的技术栈 本项目技术栈基于 ES6、vue3、pinia、vue-router 、vite 、axios 和 element-plus http:/…

企业社会信任数据,信任指数(2004-2022年)

企业社会信任是指公众对企业及其行为的信任程度&#xff0c;这种信任度是基于企业的商业行为、产品质量、服务态度、信息披露透明度和社会责任履行等多方面因素的综合评估。 2004年&#xff0d;2022年 企业社会信任数据&#xff08;大数据&#xff09;https://download.csdn.n…

【网络】高级IO——select版本TCP服务器

目录 前言 一&#xff0c;select函数 1.1.参数一&#xff1a;nfds 1.2.参数二&#xff1a; readfds, writefds, exceptfds 1.2.1.fd_set类型和相关操作宏 1.2.2.readfds, writefds, exceptfds 1.2.3.怎么理解 readfds, writefds, exceptfds是输入输出型参数 1.3.参数三…

LeetCode[中等] 3. 无重复字符的最长子串

给定一个字符串 s &#xff0c;请你找出其中不含有重复字符的 最长子串 的长度。 思路&#xff1a;滑动窗口&#xff0c;设置左右指针left与right&#xff0c;maxLength存储长度 利用HashSet性质&#xff0c;存储滑动窗口中的字符 如果没有重复的&#xff0c;那么right继续向…