利用ROS框架搭建云平台提供机器人服务

2023-05-16

我们要怎么做呢

我们在云平台我们识别物体之后输出的是全局的二维码坐标 x y z
我们接下来要做两件事情 一种是使用云端的服务 (在ROS中的表现形式是云平台提供的action)。
第二种是请求云端的数据(可以以客户端向云平台请求serve服务的形式)。
第一种应该是一种机器人向云平台发送一个action请求,然后不断的将相关图像或者红外的topic进行发送,然后云平台返回检测结果


这个action咋写?我们先展示《ROS_ROBOT_PROGRAMMING》中的demo

在这里插入图片描述
action_server.cpp

#include <ros/ros.h>
#include <actionlib/server/simple_action_server.h>
#include <ros_tutorials_action/FibonacciAction.h>

class FibonacciAction
{
    protected:
      ros::NodeHandle nh_;
      actionlib::SimpleActionServer<ros_tutorials_action::FibonacciAction> as_;

      std::string action_name_;//定义action的名字

      ros_tutorials_action::FibonacciFeedback feedback_;
      ros_tutorials_action::FibonacciResult result_;
    public:
      FibonacciAction(std::string name):
        as_(nh_,name,boost::bind(&FibonacciAction::executeCB,this,_1),false),
        action_name_(name)
        {
            as_.start();
        }
      ~FibonacciAction(void)
      {
      }

      void executeCB(const ros_tutorials_action::FibonacciGoalConstPtr &goal)
      {

        ros::Rate r(1);       // Loop Rate: 1Hz
        bool success = true;  // Used as a variable to store the success or failure of an action

        // Setting Fibonacci sequence initialization,
        // add first (0) and second message (1) of feedback.
        feedback_.sequence.clear();
        feedback_.sequence.push_back(0);
        feedback_.sequence.push_back(1);

        // Notify the user of action name, goal, initial two values of Fibonacci sequence
        ROS_INFO("%s: Executing, creating fibonacci sequence of order %i with seeds %i, %i", action_name_.c_str(), goal->order, feedback_.sequence[0], feedback_.sequence[1]);

        // Action contents
        for(int i=1; i<=goal->order; i++)
        {
            // Confirm action cancellation from action client
            if (as_.isPreemptRequested() || !ros::ok())
            {
                // Notify action cancellation
                ROS_INFO("%s: Preempted", action_name_.c_str());
                // Action cancellation and consider action as failure and save to variable
                as_.setPreempted();
                success = false;
                break;
            }
            // Store the sum of current Fibonacci number and the previous number in the feedback
            // while there is no action cancellation or the action target value is reached.
            feedback_.sequence.push_back(feedback_.sequence[i] + feedback_.sequence[i-1]);
            // publish the feedback
            as_.publishFeedback(feedback_);
            // this sleep is not necessary, the sequence is computed at 1 Hz for demonstration purposes
            r.sleep();
        }

        // If the action target value is reached,
        // transmit current Fibonacci sequence as the result value.
        if(success)
        {
            result_.sequence = feedback_.sequence;
            ROS_INFO("%s: Succeeded", action_name_.c_str());
            // set the action state to succeeded
            as_.setSucceeded(result_);
        }
      }

};


int main(int argc, char** argv)                     // Node Main Function
{
  ros::init(argc, argv, "action_server");           // Initializes Node Name
  FibonacciAction fibonacci("ros_tutorial_action"); // Fibonacci Declaration (Action Name: ros_tutorial_action)
  ros::spin();                                      // Wait to receive action goal
  return 0;
}

action_client.cpp

#include <ros/ros.h>                              // ROS Default Header File
#include <actionlib/client/simple_action_client.h>// action Library Header File
#include <actionlib/client/terminal_state.h>      // Action Goal Status Header File
#include <ros_tutorials_action/FibonacciAction.h> // FibonacciAction Action File Header

int main (int argc, char **argv)          // Node Main Function
{
  ros::init(argc, argv, "action_client"); // Node Name Initialization

  // Action Client Declaration (Action Name: ros_tutorial_action)
  actionlib::SimpleActionClient<ros_tutorials_action::FibonacciAction> ac("ros_tutorial_action", true);

  ROS_INFO("Waiting for action server to start.");
  ac.waitForServer(); //wait for the action server to start, will wait for infinite time

  ROS_INFO("Action server started, sending goal.");
  ros_tutorials_action::FibonacciGoal goal; // Declare Action Goal
  goal.order = 20;    // Set Action Goal (Process the Fibonacci sequence 20 times)
  ac.sendGoal(goal);  // Transmit Action Goal

  // Set action time limit (set to 30 seconds)
  bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));

  // Process when action results are received within the time limit for achieving the action goal
  if (finished_before_timeout)
  {
    // Receive action target status value and display on screen
    actionlib::SimpleClientGoalState state = ac.getState();
    ROS_INFO("Action finished: %s",state.toString().c_str());
  }
  else
    ROS_INFO("Action did not finish before the time out.");

  //exit
  return 0;
}

Fibonacci.action

#goal definition
int32 order
---
#result definition
int32[] sequence
---
#feedback
int32[] sequence

分析时间

Goal应该包括
string ID(表明client的身份或者说表明接下去需要传输信息到云端的时候,topic的namespace前缀)
int32 ServID:请求服务的ID,这里我们可以设定需要识别二维码的服务是1,需要物体识别的服务是2
int32 Time:请求服务的最长时长(如果没有为0的话默认时常最长600,即十分钟)
Result应该包括
int32 DetectNum:检测的数量
Feedback应该包括
Object[] detectObject:检测到的物品信息array

我准备解析好Goal之后直接调用系统命令行roslaunch 不过这时候我的topic输出的是检测到的二维码,没有进行判断是否是之前的
所以我还需要监听roslaunch的输出的物体topic,然后存储在本地,然后每一次出来就和本地的做对比,小于阈值就忽略,大于阈值更新,并且result和feedback都进行添加。

存储二维码信息

每次检测到二维码我都需要检查是否在数据库中存在,进行一系列的逻辑判断,那么就需要在ROS的pkg中与数据库交互。
这里我选择SQLite,通过这里的教程以及前面WHERE条件筛选就可以大致的写出了

login database:
sqlite3 test.db
check database at this time:
.databases
turn DB into sql format:
sqlite3 test.db .dump > test.sql
ATTACH DATABASE file_name AS database_name:
ATTACH DATABASE 'test.db' as 'TEST';
(default is main)
DETACH DTABASE :
DETACH DATABASE 'Alias-Name';
CREATE TABLE :
CREATE TABLE database_name.table_name(
   column1 datatype  PRIMARY KEY(one or more columns),
   column2 datatype,
   column3 datatype,
   .....
   columnN datatype,
);
DROP TABLE :
DROP TABLE database_name.table_name;
datatype:https://www.runoob.com/sqlite/sqlite-data-types.html
大概的有INT TEXT CHAR(50) REAL 没有时间 时间也是使用TEXT、REAL 或 INTEGER 值
比如
sqlite> CREATE TABLE COMPANY(
   ID INT PRIMARY KEY     NOT NULL,
   NAME           TEXT    NOT NULL,
   AGE            INT     NOT NULL,
   ADDRESS        CHAR(50),
   SALARY         REAL
);
check out table 
.tables

格式化输出

您可以使用下列的点命令来格式化输出为本教程下面所列出的格式:

sqlite>.header on
sqlite>.mode column
sqlite>.timer on
sqlite>

非ROS进行条件筛选的代码

首先如何通过CMakeLists.txt对cpp非ROS的工程进行构建呢?
sqlite的地址为 sqlite3: /usr/bin/sqlite3 /usr/include/sqlite3.h
使用g++命令的话是$g++ test.c -l sqlite3
那么如果要使用CMake如何构建呢?
参考:https://www.hahack.com/codes/cmake/
https://www.linuxidc.com/Linux/2019-03/157760.htm
https://www.jianshu.com/p/bbf68f9ddffa
https://zhuanlan.zhihu.com/p/59161370

cmake_minimum_required (VERSION 2.8)
project(test-demo)
# 查找当前目录中的所有源文件,并将结果列表存放在变量DIR_SRCS中
aux_source_directory(. DIR_SRCS)

# 指定可执行文件名称,PROJECT_NAME是前面定义的project名称
add_executable(${PROJECT_NAME} ${DIR_SRCS})
target_link_libraries(${PROJECT_NAME} sqlite3)

ls

build CMakeLists.txt main.cpp

mkdir build && cd build &&cmake …
ls

CMakeCache.txt CMakeFiles cmake_install.cmake Makefile

make之后就会出现
test-demo
完美运行.

如何在ROS里面使用SQLite

一开始我一直以为需要怎么怎么样,比如https://stackoverflow.com/questions/60064778/how-to-build-a-ros-node-that-uses-sqlite3(按照这样不行)
通过https://www.jianshu.com/p/75fa7b1f3938认为

find_package(catkin REQUIRED COMPONENTS nodelet)
catkin执行到这个语句时,就会导出的nodelet的include路径,库等也添加到catkin前缀的变量中。例如,catkin_INCLUDE_DIRS不仅包含catkin的include路径,还包含了nodelet,这在后面会用到。
当然,我们可以只选择找nodelet的:
find_package(nodelet)
很可惜这样的做法会令nodelet路径,库等不会被添加到catkin变量中,从而生成了例如nodelet_INCLUDE_DIRS,nodelet_LIBRARIES这样的变量等。

所以我将CMakeLists.txt相关部分改为

find_package(sqlite3)
include_directories(
  include ${catkin_INCLUDE_DIRS}
  ${nodelet_INCLUDE_DIRS}
)
add_dependencies(sqlite_demo ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(sqlite_demo
  ${catkin_LIBRARIES}
  ${nodelet_LIBRARIES}
)

然后我发现#include <sqlite3.h>没写的时候是这样

/home/asber/catkin_ws/src/arcodelistener/src/sqlite_demo.cpp:6:4: error: ‘sqlite3’ was not declared in this scope
    sqlite3 *db;
    ^
/home/asber/catkin_ws/src/arcodelistener/src/sqlite_demo.cpp:6:13: error: ‘db’ was not declared in this scope
    sqlite3 *db;
             ^
/home/asber/catkin_ws/src/arcodelistener/src/sqlite_demo.cpp:10:56: error: ‘sqlite3_open’ was not declared in this scope
    rc = sqlite3_open("/home/asber/sqlite3/test.db", &db);
                                                        ^
/home/asber/catkin_ws/src/arcodelistener/src/sqlite_demo.cpp:13:69: error: ‘sqlite3_errmsg’ was not declared in this scope
       fprintf(stderr, "Can't open database: %s\n", sqlite3_errmsg(db));
                                                                     ^
/home/asber/catkin_ws/src/arcodelistener/src/sqlite_demo.cpp:18:20: error: ‘sqlite3_close’ was not declared in this scope
    sqlite3_close(db);

写的时候是这样

CMakeFiles/sqlite_demo.dir/src/sqlite_demo.cpp.o: In function `main':
sqlite_demo.cpp:(.text.startup+0x1d): undefined reference to `sqlite3_open'
sqlite_demo.cpp:(.text.startup+0x45): undefined reference to `sqlite3_close'
sqlite_demo.cpp:(.text.startup+0x65): undefined reference to `sqlite3_errmsg'

所以头文件找到了,但是还是没找到库文件
我看这里https://www.cnblogs.com/sgdd123/p/8419964.html或者https://blog.csdn.net/qq_28306361/article/details/85142192使用opencv的时候也使用到了
#include<opencv2/opencv.hpp>
#include<opencv2/highgui/highgui.hpp>
#include<opencv2/imgproc/imgproc.hpp>

FIND_PACKAGE( OpenCV REQUIRED )
AUX_SOURCE_DIRECTORY(src/. DIR_SRCS)
ADD_EXECUTABLE(cylinder ${DIR_SRCS}  )
target_link_libraries(cylinder ${catkin_LIBRARIES}) 
target_link_libraries(cylinder ${OpenCV_LIBRARIES} )

所以我依葫芦画瓢

find_package(SQLite3 REQUIRED)
include_directories(
  include ${catkin_INCLUDE_DIRS}
  ${nodelet_INCLUDE_DIRS}
)
add_executable(sqlite_demo
  src/sqlite_demo.cpp
)
add_dependencies(sqlite_demo ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(sqlite_demo
  ${catkin_LIBRARIES}
  ${nodelet_LIBRARIES}
)

但是catkin_make的时候还是

  Could not find a package configuration file provided by "SQLite3" with any
  of the following names:

    SQLite3Config.cmake
    sqlite3-config.cmake

后来想一想,直接按照上面非ROS的CMakeLists.tst后面写

target_link_libraries(sqlite_demo
  ${catkin_LIBRARIES}
  sqlite3
)

发现,Oh ye, 可以.
所以得出结论1.CMake的知识还是要多看 2.ROS对CMake进行上层封装,所以可以直接像CMake里面一下在target_link_libraries里面加入需要的系统库就好了

IT’S ABOUT TIME TO CODING

写一个存入并且判断的pkg,
https://www.runoob.com/sqlite/sqlite-c-cpp.html
sqlite> CREATE TABLE ARCODE(
…> ID INT PRIMARY KEY NOT NULL,
…> NAME TEXT NOT NULL,
…> X REAL NOT NULL,
…> Y REAL NOT NULL,
…> Z REAL NOT NULL,
…> TIME REAL
…> );
https://www.cnblogs.com/kanego/archive/2012/07/06/2578748.html
回调函数中如何调用类中的非静态成员变量或非静态成员函数
C语言中void*详解及应用

ARCODE的主函数

#include "ros/ros.h"
#include "turtlesim/Pose.h"
#include "ar_track_alvar_msgs/AlvarMarkers.h"
#include "ar_track_alvar_msgs/AlvarMarker.h"
#include "geometry_msgs/PoseStamped.h"
#include <tf/transform_listener.h> 
#include <signal.h>
#include <stdio.h>
#include <sqlite3.h>
#include <cstdlib>
#include <arcodelistener/detect_object.h>
sqlite3 *db;
void mySigintHandler(int sig)
{
  // Do some custom action.
  // For example, publish a stop message to some other nodes.
  
  // All the default sigint handler does is call shutdown()
  sqlite3_close(db);
  ROS_INFO("mySigintHandler is called! DB closed~");
  ros::shutdown();
}
// 接收到订阅的消息后,会进入消息回调函数
void chatterCallback(const ar_track_alvar_msgs::AlvarMarkers::ConstPtr msg,const tf::TransformListener &listener)
{
    // 将接收到的消息打印出来
    std::vector<ar_track_alvar_msgs::AlvarMarker> MKS = msg->markers;
    if(MKS.size()!=0)
    {
        
        for(int i=0;i<MKS.size();i++){
            geometry_msgs::PointStamped origin_point;
            origin_point.point.x=MKS[i].pose.pose.position.x;
            origin_point.point.y=MKS[i].pose.pose.position.y;
            origin_point.point.z=MKS[i].pose.pose.position.y;
            origin_point.header.frame_id=MKS[i].header.frame_id;
            origin_point.header.stamp=ros::Time();
            string name ;
            stringstream ss;
            ss<<MKS[i].id;
            ss>>name;
            cout<< name<<endl;
            try
            {
                geometry_msgs::PointStamped base_point;
                listener.transformPoint("world", origin_point, base_point);
                DetectObject obj = DetectObject(name,ArCode,base_point.point.x,base_point.point.y,
                base_point.point.z,base_point.header.stamp.toSec(),db);
                ROS_INFO("x:%f,y:%f,z:%f,time:%f",obj.x,obj.y,obj.z,obj.time);
                if(!obj.FindIfHadOne()) 
                {
                    ROS_INFO("New Recong!");
                    if(obj.InsertOne())ROS_INFO("InSert Successfully");
                    else ROS_INFO("InSert Faultly");
                }
                else
                {
                    ROS_INFO("Already Recored..");
                }
            }
            catch (tf::TransformException &ex) {
                ROS_ERROR("%s",ex.what());
                ros::Duration(0.5).sleep();
            }
        }
    }
}


int main(int argc, char **argv)
{
    
    // 初始化ROS节点
    ros::init(argc, argv, "listener", ros::init_options::NoSigintHandler);
    // 创建节点句柄
    ros::NodeHandle n;
    // 创建一个Subscriber,订阅名为chatter的topic,注册回调函数chatterCallback
    tf::TransformListener listener(ros::Duration(10));
    signal(SIGINT, mySigintHandler);
    ROS_INFO("connecting detebase!");
    char *zErrMsg = 0;
    int rc;
    rc = sqlite3_open("/home/asber/sqlite3/test.db", &db);
    if( rc ){
        fprintf(stderr, "Can't open database: %s\n", sqlite3_errmsg(db));
        exit(0);
    }else{
        fprintf(stderr, "Opened database successfully\n");
    }
    
    
    ROS_INFO("subscribe Topic ar_pose_marker");
    ros::Subscriber sub = n.subscribe<ar_track_alvar_msgs::AlvarMarkers>("/ar_pose_marker", 10, boost::bind(&chatterCallback,_1,boost::ref(listener)));
    // 循环等待回调函数
    ros::spin();
    return 0;
}

和物品识别相关的文件

#include "ros/ros.h"
#include "turtlesim/Pose.h"
#include "object_recognition_msgs/RecognizedObjectArray.h"
#include "object_recognition_msgs/RecognizedObject.h"
#include "geometry_msgs/PoseStamped.h"
#include <tf/transform_listener.h> 
#include <signal.h>
#include <stdio.h>
#include <sqlite3.h>
#include <cstdlib>
#include <arcodelistener/detect_object.h>
sqlite3 *DB;
void mySigintHandler(int sig)
{
  // Do some custom action.
  // For example, publish a stop message to some other nodes.
  
  // All the default sigint handler does is call shutdown()
  sqlite3_close(DB);
  ROS_INFO("mySigintHandler is called! DB closed~");
  ros::shutdown();
}
// 接收到订阅的消息后,会进入消息回调函数
void chatterCallback(const object_recognition_msgs::RecognizedObjectArray::ConstPtr msg,const tf::TransformListener &listener)
{
    // 将接收到的消息打印出来
    std::vector<object_recognition_msgs::RecognizedObject> OBJ = msg->objects;
    if(OBJ.size()!=0)
    {
        
        for(int i=0;i<OBJ.size();i++){
            geometry_msgs::PointStamped origin_point;
            // string key =OBJ[i].type.key;
            // string db =OBJ[i].type.db;
            origin_point.point.x=OBJ[i].pose.pose.pose.position.x;
            origin_point.point.y=OBJ[i].pose.pose.pose.position.y;
            origin_point.point.z=OBJ[i].pose.pose.pose.position.z;
            origin_point.header.frame_id=OBJ[i].header.frame_id;
            origin_point.header.stamp=ros::Time();
            try
            {
                geometry_msgs::PointStamped base_point;
                listener.transformPoint("/map", origin_point, base_point);
                DetectObject obj = DetectObject(OBJ[i].type.key,RegnizedObj,base_point.point.x,base_point.point.y,
                base_point.point.z,base_point.header.stamp.toSec(),DB);
                ROS_INFO("OBJ:x:%f,y:%f,z:%f,time:%f",obj.x,obj.y,obj.z,obj.time);
                if(!obj.FindIfHadOne()) 
                {
                    ROS_INFO("New Recong!");
                    if(obj.InsertOne())ROS_INFO("InSert Successfully");
                    else ROS_INFO("InSert Faultly");
                }
                else
                {
                    ROS_INFO("Already Recored.. OR FindIfExistFaled");
                }
            }
            catch (tf::TransformException &ex) {
                ROS_ERROR("%s",ex.what());
                ros::Duration(0.5).sleep();
            }
        }
    }
}


int main(int argc, char **argv)
{
    // 初始化ROS节点
    ros::init(argc, argv, "listener", ros::init_options::NoSigintHandler);
    // 创建节点句柄
    ros::NodeHandle n;
    // 创建一个Subscriber,订阅名为chatter的topic,注册回调函数chatterCallback
    tf::TransformListener listener(ros::Duration(10));
    signal(SIGINT, mySigintHandler);
    ROS_INFO("connecting detebase!");
    char *zErrMsg = 0;
    int rc;
    rc = sqlite3_open("/home/asber/sqlite3/test.db", &DB);
    if( rc ){
        fprintf(stderr, "Can't open database: %s\n", sqlite3_errmsg(DB));
        exit(0);
    }else{
        fprintf(stderr, "Opened database successfully\n");
    }
    
    
    ROS_INFO("subscribe Topic ar_pose_marker");
    ros::Subscriber sub = n.subscribe<object_recognition_msgs::RecognizedObjectArray>("/recognized_object_array", 10, boost::bind(&chatterCallback,_1,boost::ref(listener)));
    // 循环等待回调函数
    ros::spin();
    return 0;
}

与数据库交互的类的头文件

#include <string>
#include <stdio.h>
#include <stdlib.h>
#include <sqlite3.h>
#include <cstdlib>
#include <cstring>
#include <map>
#include <iostream>
#include <boost/format.hpp>
//写一个类来存储检测到的物体并且判断是否在数据库中出现过
//目前已经完成了创建表,检查是否在一定范围内存在相同物体,和插入表,但是现在插入的数据
/*大体如这样
TYPE        NAME        X            Y            Z           TIME        
----------  ----------  -----------  -----------  ----------  ------------
0           TEMP        -0.00286071  -0.00277253  0.610729    1583410000.0
0           TEMP        0.163541     0.163846     0.883642    1583410000.0
TYPE 0 都是ARCODE还好 主要的是NAME 我现在的ID都是INT 无法识别toilet还是啥的
可能需要根据ID赋值NAME,之后到院里再看看能不能提取ARCODE的信息
然后我手动设定键值对 be4814630fa4e7a722eecd7f1c000ae3  可乐
*/
using  std::string;
using namespace std;


enum objectType { ArCode = 0 , RegnizedObj = 1, Other = 2};
#define threshold 0.2
class DetectObject
{
    private:
      sqlite3 *db;
    public:
      string name;
      objectType type;
      float x;
      float y;
      float z;
      float time;


      DetectObject();
      DetectObject(string id,objectType type,float x,float y,float z,float time,sqlite3 *db);
      ~DetectObject();
      bool FindIfHadOne();
      bool InsertOne();
      bool CreateTable();
      bool DelectTable();
      // const char* to_string();
};

与数据库交互的类的cpp文件

#include "arcodelistener/detect_object.h"

DetectObject::DetectObject()
{
}

DetectObject::DetectObject(string id,objectType type,float x,float y,float z,float time,sqlite3 *db)
{

    this->type = type;
    this->x = x;
    this->y = y;
    this->z = z;
    this->time = time;
    this->db = db;
    map<string,string> LocationMap;
    map<string,string> ObjectMap;
    ObjectMap.insert(pair<string,string> ("be4814630fa4e7a722eecd7f1c000ae3","可乐"));
    LocationMap.insert(pair<string,string>("0","厕所"));
    LocationMap.insert(pair<string,string>("1","办公室"));
    if(this->type==ArCode)
    {
        this->name=LocationMap[id];
    }
    else if(this->type==RegnizedObj)
    {
        this->name=ObjectMap[id];
    }
    else
    {
        this->name="Other Type";
    }
    cout<<"name is :"<<this->name<<endl;
}

static int callback(void *NotUsed, int argc, char **argv, char **azColName){
   int i;
   for(i=0; i<argc; i++){
      printf("%s = %s\n", azColName[i], argv[i] ? argv[i] : "NULL");
   }
   printf("\n");
   return 0;
}

bool DetectObject::CreateTable()
{
    char *zErrMsg = 0;
    char *sql;
    int  rc;
   /* Create SQL statement */
   sql = "CREATE TABLE MYLIB( "\
        "TYPE INT NOT NULL,"\
        "NAME TEXT NOT NULL,"\
        "X REAL NOT NULL,"\
        "Y REAL NOT NULL,"\
        "Z REAL NOT NULL,"\
        "TIME REAL );";
    rc = sqlite3_exec(db, sql, callback, 0, &zErrMsg);
    if( rc != SQLITE_OK ){
    fprintf(stderr, "SQL error: %s\n", zErrMsg);
        sqlite3_free(zErrMsg);
        return false;
    }else{
        fprintf(stdout, "Table created successfully\n");
        return true;
    }
}

bool DetectObject::DelectTable()
{
    char *zErrMsg = 0;
    char *sql;
    int  rc;
   /* Create SQL statement */
   sql = "DROP TABLE MYLIB;";
    rc = sqlite3_exec(db, sql, callback, 0, &zErrMsg);
    if( rc != SQLITE_OK ){
    fprintf(stderr, "SQL error: %s\n", zErrMsg);
        sqlite3_free(zErrMsg);
        return false;
    }else{
        fprintf(stdout, "Delect Table successfully\n");
        return true;
    }
}

using namespace std;
using namespace boost;
bool DetectObject::InsertOne()
{
    char *zErrMsg = 0;
    int rc;
    format fmt( "INSERT INTO MYLIB (TYPE,NAME,X,Y,Z,TIME) VALUES (%1%,'%2%',%3%,%4%,%5%,%6%);" );
    fmt % type;fmt % name;fmt % x ;fmt % y ;fmt % z ;fmt % time ;
    string str = fmt.str();
    cout<<"Insert Command is :"<<str<<endl;
    const char *mysql = str.c_str();
    rc = sqlite3_exec(db, mysql, callback, 0, &zErrMsg);
    if( rc != SQLITE_OK ){
        fprintf(stderr, "InsertOne SQL error: %s\n", zErrMsg);
        sqlite3_free(zErrMsg);
        return false;
    }else{
        fprintf(stdout, "Insert data successfully\n");
        return true;
    }
}

static int Findcallback(void *exist, int argc, char **argv, char **azColName){
   int i;
   for(i=0; i<argc; i++){
      printf("%s = %s\n", azColName[i], argv[i] ? argv[i] : "NULL");
   }
   printf("\n");
   *(bool*)exist = true;//NB
   return 0;
}

bool DetectObject::FindIfHadOne()
{
    char *zErrMsg = 0;
    int rc;
    bool exist = false;
    format fmt( "SELECT * from MYLIB WHERE X BETWEEN %1% AND %2% AND Y BETWEEN %3% AND %4% AND Z BETWEEN %5% AND %6% AND TYPE = %7%;" );
    fmt % (x-threshold) ;fmt % (x+threshold) ;fmt % (y-threshold) ;fmt % (y+threshold) ;fmt % (z-threshold) ;fmt % (z+threshold) ;fmt % type;
    string str = fmt.str();
    const char *mysql = str.c_str();
    rc = sqlite3_exec(db, mysql, Findcallback, (void*)&exist, &zErrMsg);
    if( rc != SQLITE_OK ){
        fprintf(stderr, "FindIfHadOne SQL error: %s\n", zErrMsg);
        sqlite3_free(zErrMsg);
        return true;
    }else{
        fprintf(stdout, "Operation done successfully\n");
        return exist;
    }
}

DetectObject::~DetectObject()
{
}

AR识别的launch文件

<launch>

    <node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
        <param name="video_device" value="/dev/video0" />
        <param name="image_width" value="640" />
        <param name="image_height" value="480" />
        <param name="pixel_format" value="yuyv" />
        <param name="camera_frame_id" value="usb_cam" />
        <param name="io_method" value="mmap"/>

        <param name="camera_info_url" type="string" value="file://$(find robot_vision)/camera_calibration.yaml" />
    </node>

    <node pkg="tf" type="static_transform_publisher" name="world_to_cam" 
          args="0 0 0.5 0 1.57 0 world usb_cam 1 " />
        
    <arg name="marker_size" default="20" />
    <arg name="max_new_marker_error" default="0.08" />
    <arg name="max_track_error" default="0.2" />
    <arg name="cam_image_topic" default="/usb_cam/image_raw" />
    <arg name="cam_info_topic" default="/usb_cam/camera_info" />
    <arg name="output_frame" default="/usb_cam" />
        
    <node name="ar_track_alvar" pkg="ar_track_alvar" type="individualMarkersNoKinect" respawn="false" output="screen">
        <param name="marker_size"           type="double" value="$(arg marker_size)" />
        <param name="max_new_marker_error"  type="double" value="$(arg max_new_marker_error)" />
        <param name="max_track_error"       type="double" value="$(arg max_track_error)" />
        <param name="output_frame"          type="string" value="$(arg output_frame)" />

        <remap from="camera_image"  to="$(arg cam_image_topic)" />
        <remap from="camera_info"   to="$(arg cam_info_topic)" />
    </node>

    <!-- rviz view /-->
    <node pkg="rviz" type="rviz" name="rviz" args="-d $(find robot_vision)/config/ar_track_camera.rviz"/>
    <node pkg="arcodelistener" type="ar_code_listener" name="local2global_tf_transfer" />
</launch>

物品识别的launch文件(里面包括开启仿真节点)

<launch>
  <!-- SIMULATION -->
  <include file="$(find turtlebot_gazebo)/launch/turtlebot_world.launch"/>
  <!--CONTROL -->
  <include file="$(find turtlebot_teleop)/launch/keyboard_teleop.launch"/>
  <!-- AMCL -->
  <arg name="map_file" default="/home/asber/turtlebot_custom_maps/tutorial.yaml"/>
  <arg name="amcl_demo" default="$(find turtlebot_gazebo)/launch/amcl_demo.launch"/>
  <include file="$(arg amcl_demo)">
    <arg name="map_file" value="$(arg map_file)"/>
  </include>
  <node pkg="rviz" type="rviz" name="rviz" args="-d $(find robot_vision)/config/obj.rviz"/>
  <node pkg="object_recognition_core" type="detection" name="obj_detection" args="-c /home/asber/ork_ws/src/ork_linemod/conf/detection.ros.ork"/>
  <node pkg="arcodelistener" type="ORK_listener" name="OBJ_local2global_tf_transfer"  output="screen"/>
</launch>

我编写代码的时候参考的:
ROS节点的初始化及退出详解(ros::init、SIGINT、ros::ok、ros::NodeHandle)
标准C++中的string类的用法总结
enum类型变量的使用和赋值
C语言中值传递、指针传递和引用传递

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

利用ROS框架搭建云平台提供机器人服务 的相关文章

  • 使用WTGAHRS2(JY-GPSIMU)在ROS中读取数据并发布话题

    目录 IMU简介 驱动程序 IMU串口通信协议 程序 效果 IMU简介 十轴惯性导航传感器WTGAHRS2传感器集成高精度的陀螺仪 加速度计 地磁场传感器 GPS 模块 采用高性能的微处理器和先进的动力学解算与卡尔曼动态滤波算法 能够快速求
  • ROS之QtCreator开发环境搭建

    文章目录 系统环境 官方教程 安装 卸载 使用 导入工作空间 构建与运行 编写测试程序 系统环境 操作系统 Ubuntu20 04 ROS版本 Noetic 官方教程 按照官方教程或者下面笔记中的内容均能进行环境搭建 笔记中另外做了部分补充
  • ros+arduino学习(六):重构ros_lib库文件

    前言 ros lib是arduino程序和ros连接的库文件 通过使用这些库文件和相关函数 可以在arduino上通过编程使得arduino硬件开ros节点程序 这样arduino硬件就可以与上位机通过话题进行通讯 从而把arduino从传
  • ROS学习(1)——ROS1和ROS2的区别

    因为机器人是一个系统工程 它包括了机械臂结构 电子电路 驱动程序 通信框架 组装集成 调试和各种感知决策算法等方面 任何一个人甚至是一个公司都不可能完成机器人系统的研发工作 但是我们又希望自己能造出一个机器人跑一跑 验证一下自己的算法 所以
  • Ubuntu16.04安装ROS Kinetic详细步骤

    文章目录 ROS安装 配置Ubuntu软件仓库 设置sources list 设置密钥 更新Debian软件包索引 安装ROS 初始化 rosdep 环境配置 构建工厂依赖 测试安装 开发环境 ROS安装 ROS Kinetic只支持Wil
  • Ubuntu下vscode配置ROS环境

    摘要 最近准备放弃用clion开发ROS使用更主流的vscode 整理一下在ubuntu18 04下的VSCode安装和ROS环境配置流程 安装 方法一 软件商店安装 个人还是推荐使用ubuntu软件下载vscode 简单不容易出错 方法二
  • ROS 笔记(01)— Ubuntu 20.04 ROS 环境搭建

    ROS 官网 https www ros org ROS 中文官网 http wiki ros org cn 1 系统和 ROS 版本 不同的 ROS 版本所需的 ubuntu 版本不同 每一版 ROS 都有其对应版本的 Ubuntu 切记
  • 解决ros安装 使用roscore命令测试问题

    本人安装教程完成ROS的安装后 在进行测试如图1命令 出现 解决办法输入完命令1后要输入命令2才行 即可测试成功 测试成功的界面如下
  • Raspberry Pi 上 ROS 服务器/客户端通过GPIO 驱动硬件

    ROS 服务 现在 想象一下你在你的电脑后面 你想从这个服务中获取天气 你 在你身边 被认为是客户端 在线天气服务是服务器 您将能够通过带有 URL 的 HTTP 请求访问服务器 将 HTTP URL 视为 ROS 服务 首先 您的计算机将
  • 局域网下ROS多机通信的网络连接配置

    1 在路由器设置中固定各机器IP地址 在浏览器中输入路由器的IP地址 例如TP LINK路由器的IP为 192 168 1 1 进入登录页面后 输入用户名和密码登录 用户名一般为admin 密码为自定义 在 基本设置 gt LAN设置 gt
  • 【ROS】usb_cam相机标定

    1 唠叨两句 当我们要用相机做测量用途时 就需要做相机标定了 不然得到的计算结果会有很大误差 标定的内容包括三部分 内参 外参还有畸变参数 所以标定的过程就是要求得上面这些参数 以前弄这个事估计挺麻烦 需要做实验和计算才能得到 现在通过ro
  • 可视化点云

    我在找到的视差图像上有来自 gpu reprojectImageTo3D 的 3D 点 我现在想显示这个点云 如何将找到的点云转换为OpenCV to sensor msgs PointCloud2 我不需要发布点云 这仅用于调试可视化 是
  • 无法在 ROS 中使用本地安装的 Protocol Buffer

    我已经安装了协议缓冲区 https developers google com protocol buffers 本地 ROS包的目录结构如下 CMakeLists txt package xml include addressbook p
  • Caught exception in launch(see debug for traceback)

    Caught exception in launch see debug for traceback Caught exception when trying to load file of format xml Caught except
  • 在 Ubuntu 18.10 上安装 ROS Melodic

    I can t是唯一对 Cosmic 与 Wayland 和 Melodic 的组合感兴趣的人 我会坦白说 我似乎已经在 XPS 13 9370 上成功管理了此操作 或者至少安装脚本 最终 成功完成 然而 有一个非常棘手的解决方法 无论结果
  • catkin_make 编译报错 Unable to find either executable ‘empy‘ or Python module ‘em‘...

    文章目录 写在前面 一 问题描述 二 解决方法 参考链接 写在前面 自己的测试环境 Ubuntu20 04 一 问题描述 自己安装完 anaconda 后 再次执行 catkin make 遇到如下问题 CMake Error at opt
  • 如何订阅“/scan”主题、修改消息并发布到新主题?

    我想通过订阅message ranges来改进turtlebot3的LDS 01传感器 通过应用一些算法修改messange ranges并将其发布到新主题 如下所示 但是当我运行编码时出现错误 错误是 遇到溢出的情况 错误是 运行时警告
  • ROS 问题:libQt5Core.so.5:无法打开共享对象文件:没有这样的文件或目录

    当我跑步时 rosrun turtlesim turtlesim node 在 Ubuntu 上 我收到以下消息 opt ros noetic lib turtlesim turtlesim node 加载共享库时出错 libQt5Core
  • ROS中spin和rate.sleep的区别

    我是 ROS 新手 正在尝试了解这个强大的工具 我很困惑spin and rate sleep功能 谁能帮助我了解这两个功能之间的区别以及何时使用每个功能 ros spin and ros spinOnce 负责处理通信事件 例如到达的消息
  • 安装 ROS 时 Cmake 未检测到 boost-python

    我一直在尝试在我的 Mac 上安装 ROS 并根据不同版本的 boost 使用不同的库解决了错误 然而 似乎有一个库甚至没有检测到 boost python 这是我得到的错误 CMake Error at usr local share c

随机推荐

  • Python全局变量和局部变量(超详细,纯干货,保姆级教学)

    全局变量定义 在函数外部定义的变量 所有函数内部都可以使用这个变量 局部变量定义 在函数内部定义的变量 这个变量只能在定义这个变量的函数内部使用 第一种 xff1a global定义全局变量在自定义函数内部 定义看起来一愣一愣的 xff0c
  • stm32——手动移植HAL库以及错误解决方案(以STM32F103ZE为例)

    寄存器编程的缺点 xff1a 代码可读性差 xff0c 二次开发难度大 xff0c 而且要每次都查阅用户手册 xff0c 非常麻烦 HAL库 xff1a HAL库封装出了一层通用性的接口 xff0c 标准化了一套通用性的接口 xff0c 大
  • MATLAB在线编辑器online

    话不多说直接上网址 https matlab mathworks com 这个和下载的MATLAB功能一模一样 xff0c 这是我找了几个例子运行出来的结果 xff0c 和我想要的一模一样 xff0c 不过对于大多数人而言 xff0c 这个
  • stm32——使用结构体描述寄存器映射

    将地址信息放在一个头文件中方便管理 xff0c 存放地址和偏移量 STM32的外设寄存器的组织形式是 基于基地址 43 寄存器偏移地址 比如 xff0c 在RCC的基地址基础上 xff0c 偏移0x00得到RCC CR寄存器 xff0c 偏
  • 江科大stm32-概述

    第一章 STM32概述 1 1 资源介绍 STM32F103C8T6 51单片机使用的是5V供电 xff0c 还有USB输出的电压也是5V xff0c 5V是不在这个供电电压范围内的 xff0c 不能直接给STM32供电 xff0c 如果是
  • 在eclipse中查看你用的tomcat的路径

    打开eclipse xff0c 选择window gt Preferences gt Server gt Runtime Environments选择你的tomcat然后点Edit xff0c 就会出现它的路径了
  • 安装龙蜥或CentOS 7时出现dracut- initqueue timeout解决方法

    在安装龙蜥7 9操作系统时 xff0c 出现dracut initqueue timeout starting starting timeout scripts报错 CentOS 7 9出现此问题也可以参考同样的方法 如何制作启动盘和系统盘
  • 视觉标记定位aruco使用

    本文的目的是实现生成一张marker broad图片 xff0c 告诉标记检测程序tag在真实世界中的实际大小 检测成功后得到marker的id 四个角点坐标 marker到相机的平移和旋转 xff11 xff0e 下载安装参考 openc
  • github进行修改

    1 xff09 git status xff1a 可以让我们时刻掌握仓库当前的状态 2 xff09 git diff 文件名 xff1a 查看改变的详细信息 xff0c 显示的结果是Unix通用的diff格式 步骤 xff1a 1 修改文件
  • C# 内存与性能优化

    C 内存与性能优化 https www jianshu com p d56f79d83ebd 前两周分享了资源配置与资源管理 xff0c 今天分享一种特殊的资源脚本数据 在Unity项目中 xff0c 我们通常使用C 编写脚本 xff0c
  • Gazebo仿真错误与技巧

    xff08 1 xff09 创建的环境不能保存 打开gazebo创建环境以后 xff0c 不能保存 xff0c 在打开是需要加权限 xff08 sudo xff09 xff0c 详细说明 如果是build可以先保存成模型 xff0c 然后再
  • 《Android入门之旅》

    因为本人在公司任职Java和JavaWeb相关开发工作 EXTJS和JQUERY近年来在网站中使用广泛 EXT江湖对我帮助很大 该书由浅入深地解析了Ext框架的方方面面 xff0c 包括JS基础 Ext的DOM和CSS封装 内置对象的扩展
  • 转发——从搭建小系统到架构分布式

    从搭建小系统到架构分布式 从搭建小系统到架构分布式 SpringBoot是目前Spring技术体系中炙手可热的框架之一 既可用于构建业务复杂的企业应用系统 xff0c 也可以开发高性能和高吞吐量的互联网应用 Spring Boot 框架降低
  • 2018-8-30华为机试第三题

    一个很明显的递归问题 package cn csu ksh import java util ArrayList import java util List import java util Scanner public class Mai
  • 海康威视web3.2开发包开发使用说明

    首言 xff1a 通过海康威视的最新web开发包工具进行js调用引入至vue项目中 xff0c 实现监控设备的对接 xff0c 监控功能的实现 3 2无插件js库同时支持插件安装的模式 目录 首言 xff1a 一 海康威视开发平台 xff1
  • 游戏的navmesh 与rvo动态避障算法(1)

    目前很多手游中如果需要寻路 xff0c 很多时候复杂地形都是需要用到navmesh xff0c 而比较常用的navmesh 系统 xff1a 1 astarpathfinding xff1a 一个老外开发的寻路插件 xff0c 内置有很多寻
  • Python3 指数函数 | numpy.power() math.pow() numpy.exp2() a**b

    对数函数用法 单纯求一个数的指数函数 xff0c 直接用a b比较好 xff1f 2 3 2的三次方 使用pow x y pow 有两种 xff0c 一种是python内置函数 xff0c 一种是math pow 使用python内置函数调
  • SVO2.0

    rpg svo pro open即svo2 0版本在上一年开源了 xff0c 对svo2 0接触了有一小段时间了 xff0c 感觉代码功能和一些函数实现等相比svo1 0版本有区别 xff0c 所以准备把这块好好总结下 xff0c 争取白话
  • ROS CMakeLists.txt中catkin_package和INCLUDE_DIRS的区别

    CMakeLists txt中 catkin package INCLUDE DIRS include 这里代表的是catkin的构建选项 xff0c INCLUDE DIRS表示将使用INCLUDE DIRS后面的内部目录include
  • 利用ROS框架搭建云平台提供机器人服务

    我们要怎么做呢 我们在云平台我们识别物体之后输出的是全局的二维码坐标 x y z 我们接下来要做两件事情 一种是使用云端的服务 xff08 在ROS中的表现形式是云平台提供的action xff09 第二种是请求云端的数据 xff08 可以