Chapter V common components of ROS

Chapter V common components of ROS

  • TF coordinate transformation to realize the transformation between different types of coordinate systems;
  • rosbag is used to record the execution process of ROS node and replay the process;
  • rqt toolbox integrates a variety of graphical debugging tools.

Achievable cases:

roslaunch turtle_tf2 turtle_tf2_demo_cpp.launch    
roslaunch turtle_tf2 turtle_tf2_demo.launch

1, TF coordinate transformation

  • Concept: generally right-handed coordinate system
  • tf2 common function package
tf2_geometry_msgs:Can ROS Message conversion to tf2 news
tf2:Constant message encapsulating coordinate transformation
tf2_ros:by tf2 Provided roscpp and rospy Binding, encapsulation, coordinate transformation, common api

http://wiki.ros.org/tf2

1. Coordinate msg message

In the subscription and publication model, the data carrier msg is an important implementation. First of all, we need to understand the commonly used msg in the coordinate transformation implementation: geometry_ Msgs / transformstamped (coordinate system positional relationship) and geometry_msgs/PointStamped (coordinate point message)

The former is used to transmit the position information related to the coordinate system, and the latter is used to transmit the information of coordinate points in a coordinate system. In coordinate transformation, the relative relationship of coordinate system and coordinate point information need to be used frequently.

  1. geometry_msgs/TransformStamped: coordinate system positional relationship
std_msgs/Header header                     #Header information
  uint32 seq                               #|--Serial number
  time stamp                               #|--Time stamp
  string frame_id                          #|--Base coordinate name
string child_frame_id                      #The name of the child coordinate
geometry_msgs/Transform transform          #Coordinate information
  geometry_msgs/Vector3 translation        #Offset
    float64 x                              #|--Offset in X direction
    float64 y                              #|--Offset in Y direction
    float64 z                              #|--Offset in Z direction
  geometry_msgs/Quaternion rotation        #Quaternion
    float64 x
    float64 y
    float64 z
    float64 w
  1. geometry_msgs/PointStamped: position information of coordinate points
std_msgs/Header header
  uint32 seq	#|--Serial number
  time stamp	#|--Time stamp
  string frame_id   #With that coordinate system as the reference
geometry_msgs/Point point 	#Specific coordinate position
  float64 x
  float64 y
  float64 z

2. Static coordinate transformation

The so-called static coordinate transformation means that the relative position between two coordinate systems is fixed.

Requirement Description:

There is an existing robot model. The core composition includes the main body and radar, each corresponding to a coordinate system. The origin of the coordinate system is located in the physical center of the main body and radar respectively. It is known that the displacement relationship between the radar origin and the main origin is as follows: x 0.2 y0.0 z0.5. At present, the radar detects an obstacle. In the radar coordinate system, the coordinates of the obstacle are (2.0, 3.0, 5.0). What are the coordinates of the obstacle relative to the main body?

  • Create Feature Pack
catkin_creat_pkg tf01_static roscpp rospy std_msgs tf2 tf2_ros tf2_geometry_msgs geometry_msgs
  • Compile it to see if you throw an exception
catkin_make

C + + implementation

  • Publish location information
#include "ros/ros.h"
#include "tf2/LinearMath/Quaternion.h" / / Euler angle conversion header file
#include "tf2_ros/static_transform_broadcaster.h "/ / contains static coordinate objects
#include "geometry_msgs/TransformStamped.h "/ / create static coordinate message
/*
    Required: publish the relationship between two coordinate systems
    technological process:
        1. Include header file
        2. Set encoding
        3. Create publish object
        4. Organization published messages
        5. Release news
        6. spin();// Just publish it once
*/
int main(int argc, char** argv)
{
    // 2. Set code
    setlocale(LC_ALL,"");
    ros::init(argc,argv,"statictf_pub");
    // 3. Create a static coordinate publishing object
    tf2_ros::StaticTransformBroadcaster tf_pub;
    // 4. Information released by the organization
    geometry_msgs::TransformStamped tfs;
    tfs.header.stamp = ros::Time::now();    // time stamp
    tfs.header.frame_id = "base_link";      // Reference coordinate system
    tfs.child_frame_id = "laster";          // Another object in relative terms
    tfs.transform.translation.x = 0.2;      // Setting last is equivalent to base_ Offset of link
    tfs.transform.translation.y = 0;
    tfs.transform.translation.z = 0.5;   
    // If the quad data has an offset, it can be added. Not every data in the message should be given a value, but the quaternion must be added in rviz 
    tf2::Quaternion tfqtn;      // Creating quaternion objects
    tfqtn.setRPY(0,0,0);        // Set laster relative to base_ Roll value, pitch value and yaw value of link. The unit of Euler angle is radian
    tfs.transform.rotation.x = tfqtn.getX();    // Set Euler angle
    tfs.transform.rotation.y = tfqtn.getY();
    tfs.transform.rotation.z = tfqtn.getZ();
    tfs.transform.rotation.w = tfqtn.getW();

    // 5. Release information
    tf_pub.sendTransform(tfs);
    // 6. spin();//  Just publish it once
    ros::spin();
    return 0;
}

View messages by:

View graphically:

# Enter rviz and directly press the command rviz

  • subscribe
#include "ros/ros.h"
#include "tf2_ros/transform_listener.h "/ / listen to the message header file, which is used to create the subscription object
#include "tf2_ros/buffer.h "/ / used to create and save data
#include "geometry_msgs/PointStamped.h "/ / create coordinate points
#include "tf2_geometry_msgs/tf2_geometry_msgs.h "/ / a header file must be added, otherwise the compilation fails
/*
    Subscriber: subscribe to publish messages, pass in a punctuation mark, and call tf for conversion
    technological process:
        1. Include header file
        2. Encoding, initialization, nodehandle (required)
        3. Create subscription object
        4. Set coordinate points
        5. Conversion algorithm implementation, call built-in implementation
        6. Output conversion results
*/
int main(int argc, char** argv) {
    setlocale(LC_ALL,"");
    // 2. Encoding, initialization, nodehandle (required)
    ros::init(argc,argv,"statictf_sub");
    // ros::NodeHandle nh;
    // 3. Create subscription object
    // 3-1. Create buffer cache
    tf2_ros::Buffer buf;
    // 3-2. Create a listening object (store the subscribed data in the buffer)
    tf2_ros::TransformListener listener(buf);
    // 4. Set coordinate points
    geometry_msgs::PointStamped ps;
    ps.header.frame_id = "laster";   // The object takes laser as the reference point
    ps.header.stamp = ros::Time::now();
    ps.point.x = 2.0;   // Coordinates with laser as reference point
    ps.point.y = 3.0;
    ps.point.z = 5.0;
    // Add hibernation before conversion
    // ros::Duration(2).sleep();
    // 5. Implement the conversion algorithm and call the built-in implementation
    ros::Rate rate(10);
    while (ros::ok()) {
        // Core code
        geometry_msgs::PointStamped ps_out;
        try{
            /* Call this function (buf. Transform (PS), "base_ link");) To include header files tf2_geometry_msgs/tf2_geometry_msgs.h */
            ps_out = buf.transform(ps,"base_link");// The conversion function buf. Transform (converted coordinate point, "base coordinate system name") will return a converted coordinate value.
            rate.sleep();
            // 6. Output conversion results
            ROS_INFO("Reference coordinate system%s",ps_out.header.frame_id.c_str());
            ROS_INFO("Coordinate value after conversion(%.2f,%.2f,%.2f)",ps_out.point.x,ps_out.point.y,ps_out.point.z);
        }
        catch(const std::exception& e){
            // std::cerr << e.what() << '\n';
            ROS_WARN("abnormal%s",e.what());
        }
        ros::spinOnce();
    }
    return 0;
}

2. Common components

  1. Viewing coordinate relationships with rviz
New window input command:rviz;
At startup rviz Medium setting Fixed Frame Is the reference coordinate system;
Click on the bottom left add Button and select in the pop-up window TF Component to display the coordinate relationship.
  1. Directly on the command line

When the relative positions between coordinate systems are fixed, the required parameters are also fixed: parent coordinate name, child coordinate system name, x offset, y offset, z offset, x roll angle, y pitch angle and z yaw angle. With the same implementation logic and different parameters, the ROS system has encapsulated special nodes, and the use method is as follows:

rosrun tf2_ros static_transform_publisher x Offset y Offset z Offset z angle of yaw y Pitch angle x Tumble angle parent coordinate system child coordinate system

Example: rosrun tf2_ros static_transform_publisher 0.2 0 0.5 0 0 0 /baselink /laser

It is also recommended to use this method to directly publish the relative information of the static coordinate system.

3. Dynamic coordinate transformation

Publisher implementation:

#include "ros/ros.h"
#Include "turnlesim / pose. H" / / location message header file
#include "tf2_ros/transform_broadcaster.h "/ / contains publishing dynamic coordinate relationships
#include "geometry_ Msgs / transformstamped. H "/ / TF coordinate message
#include "tf2/LinearMath/Quaternion.h" / / Euler angle conversion header file
/*
    Publisher: you need to subscribe to the turtle's location information, convert it into a coordinate relationship relative to the form, and publish it
    get ready:
        1. Topic: / turtle 1 / pose
        2. Message: turnlesim / pose
    technological process:
        1. Include header file;
        2. Set encoding, initialization and NodeHandle;
        3. Create a subscription object, subscribe to / turnle1 / pose
        4. The callback function processes the subscribed message: convert the location image into a relative coordinate relationship and publish it
        5. spin();
*/
void My_do_thing(const turtlesim::Pose::ConstPtr& msg) {
    // 4. The callback function processes the subscribed message: convert the location image into a relative coordinate relationship and publish it
    // a. Create publishing objects, create static objects
    static tf2_ros::TransformBroadcaster tf_tur;
    // b. Organize and publish data
    geometry_msgs::TransformStamped ts;
    ts.header.stamp = ros::Time::now();
    ts.header.frame_id = "word";    // Base coordinate system
    ts.child_frame_id = "turtle1";  // Tortoise coordinate system name
    ts.transform.translation.x = msg->x;
    ts.transform.translation.y = msg->y;
    ts.transform.translation.z = 0;
    // Coordinate system quaternion,
    /* There is no quaternion in the position information, but there is a yaw angle */
    tf2::Quaternion qtn;
    qtn.setRPY(0,0,msg->theta);
    ts.transform.rotation.x = qtn.getX();
    ts.transform.rotation.y = qtn.getY();
    ts.transform.rotation.z = qtn.getZ();
    ts.transform.rotation.w = qtn.getW();
    // c. Publish data
    tf_tur.sendTransform(ts);
}
int main(int argc, char** argv) {
    // 2. Set code, initialization and NodeHandle;
    ros::init(argc,argv,"dynamic_pub");
    ros::NodeHandle nh;
    ros::Subscriber sub = nh.subscribe<turtlesim::Pose>("/turtle1/pose",100,My_do_thing);
    // 5. spin();
    ros::spin();
    return 0;
}

effect:

*Subscriber implementation: * similar to static implementation

#include "ros/ros.h"
#include "tf2_ros/transform_listener.h "/ / listen to the message header file, which is used to create the subscription object
#include "tf2_ros/buffer.h "/ / used to create and save data
#include "geometry_msgs/PointStamped.h "/ / create coordinate points
#include "tf2_geometry_msgs/tf2_geometry_msgs.h "/ / a header file must be added, otherwise the compilation fails
/*
    Subscriber: subscribe to publish messages, pass in a punctuation mark, and call tf for conversion
    technological process:
        1. Include header file
        2. Encoding, initialization, nodehandle (required)
        3. Create subscription object
        4. Set coordinate points
        5. Conversion algorithm implementation, call built-in implementation
        6. Output conversion results
*/
int main(int argc, char** argv) {
    setlocale(LC_ALL,"");
    // 2. Encoding, initialization, nodehandle (required)
    ros::init(argc,argv,"dynamic_sub");
    // ros::NodeHandle nh;
    // 3. Create subscription object
    // 3-1. Create buffer cache
    tf2_ros::Buffer buf;
    // 3-2. Create a listening object (store the subscribed data in the buffer)
    tf2_ros::TransformListener listener(buf);
    // 4. Set coordinate points
    geometry_msgs::PointStamped ps;
    ps.header.frame_id = "turtle1";   // The object takes laser as the reference point
    ps.header.stamp = ros::Time(0.0);   // Time needs to be modified
    ps.point.x = 2.0;   // Coordinates with laser as reference point
    ps.point.y = 3.0;
    ps.point.z = 0.0;
    // Add hibernation before conversion
    ros::Duration(2).sleep();
    // 5. Implement the conversion algorithm and call the built-in implementation
    ros::Rate rate(10);
    while (ros::ok()) {
        // Core code
        geometry_msgs::PointStamped ps_out;
        try{
            /* Call this function (buf. Transform (PS), "base_ link");) To include header files tf2_geometry_msgs/tf2_geometry_msgs.h */
            ps_out = buf.transform(ps,"world");// The conversion function buf. Transform (converted coordinate point, "base coordinate system name") will return a converted coordinate value.
            rate.sleep();
            // 6. Output conversion results
            ROS_INFO("Reference coordinate system%s",ps_out.header.frame_id.c_str());
            ROS_INFO("Coordinate value after conversion(%.2f,%.2f,%.2f)",ps_out.point.x,ps_out.point.y,ps_out.point.z);
        }
        catch(const std::exception& e){
            // std::cerr << e.what() << '\n';
            ROS_WARN("abnormal%s",e.what());
        }
        ros::spinOnce();
    }
    return 0;
}

4. Multi coordinate transformation

Requirement Description:

The existing coordinate system, the parent coordinate system world, has two child systems son1, son2. The relationship between son1 and the world, and the relationship between son2 and the world are known. To find the coordinates of the origin of son1 in son2 and the coordinates of a point in son1, it is required to find the coordinates of the point in son2

  1. Create feature packs and import dependencies
  2. Create a publisher and publish two static coordinates

First create the launch folder and create the. launch file in the folder.

<launch>
    <!-- pkg:Package name type:Node type name:Topic name args:"Offset x,y,z,Flip value x,y,z Base coordinates" output="screen" -->
    <node pkg="tf2_ros" type="static_transform_publisher" name="son1" args="5 0 0 0 0 0 /world /son1" output="screen" />
    <node pkg="tf2_ros" type="static_transform_publisher" name="son2" args="3 0 0 0 0 0 /world /son2" output="screen" />
</launch>

realization:

#include "ros/ros.h"
#include "tf2_ros/transform_listener.h "/ / create receive
#include "tf2_ros/buffer.h "/ / import buffer
#include "geometry_msgs/PointStamped.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.h "/ / create the header file required by the point
#include "geometry_msgs/TransformStamped.h"
/*
    Subscriber implementation: 1. Calculate the relative relationship between son1 and son2; 2. Calculate the coordinate value of a point in son1 in son2
    technological process:
        1. Include header file
        2. Encoding, initialization, NodeHandle creation
        3. Create subscription object
        4. Write parsing logic
        5. spinOnce();

*/
int main(int argc, char** argv)
{
    // 2. Encoding, initialization and NodeHandle creation
    setlocale(LC_ALL,"");
    ros::init(argc,argv,"demo01_tfs_sub");
    ros::NodeHandle nh;
    // 3. Create subscription object
    tf2_ros::Buffer buffer;
    tf2_ros::TransformListener sub(buffer);
    // 4. Write parsing logic
    // Coordinate point
    geometry_msgs::PointStamped ps_son1;
    ps_son1.header.stamp = ros::Time::now();
    ps_son1.header.frame_id = "son1";
    ps_son1.point.x = 1.0;
    ps_son1.point.y = 2.0;
    ps_son1.point.z = 3.0;
    ros::Rate rate(10);
    while (ros::ok()){
        try{
            // 1. Calculate the relative relationship between son1 and son2
            /*
                geometry_msgs::TransformStamped lookupTransform(const std::string& target_frame, const std::string& source_frame,const ros::Time& time) const;
                Parameter 1const STD:: String & target_ Frame: the target coordinate system should be the reference coordinate system
                Parameter 2const STD:: String & source_ Frame: another point in the source coordinate system
                Parameter 3const ROS:: time & time: time (fixed writing method) ros::Time(0)
                Return value geometry_msgs::TransformStamped: the positional relationship between the source and the target coordinate system
            */
            geometry_msgs::TransformStamped ps_out1 = buffer.lookupTransform("son2","son1",ros::Time(0));
            ROS_INFO("son1 Relative and son2 Information for: parent pole:%s,Subset:%s",ps_out1.header.frame_id.c_str(),ps_out1.child_frame_id.c_str());
            ROS_INFO("Offset(%.2f,%.2f,%.2f)",ps_out1.transform.translation.x,ps_out1.transform.translation.y,ps_out1.transform.translation.z);
            // 2. Calculate the coordinate value of a coordinate point in son1 in son2
            geometry_msgs::PointStamped ps_out2 = buffer.transform(ps_son1,"son2");
            ROS_INFO("The coordinate point is%s Value in coordinates%.2f,%.2f,%.2f",ps_out2.header.frame_id.c_str(),ps_out2.point.x,ps_out2.point.y,ps_out2.point.z);
            rate.sleep();
            // 5. spinOnce();
            ros::spinOnce();
        }
        catch(const std::exception& e){
            ROS_WARN("Exception:%s",e.what());
        }
    }
    return 0;
}

5. View coordinate relationship

  1. preparation

First call rospack find tf2_tools to check whether the feature pack is included. If not, please use the following command to install it:

sudo apt install ros-noetic-tf2-tools
  1. use

After starting the coordinate system broadcast program, run the following command: (under which file is called, it will be generated under which folder)

rosrun tf2_tools view_frames.py

The following log information will be generated:

[INFO] [1592920556.827549]: Listening to tf data during 5 seconds...
[INFO] [1592920561.841536]: Generating graph in frames.pdf file...

Viewing the current directory will generate a frames.pdf file

You can directly enter the directory to open the file, or call the command to view the file: evince frames.pdf

6. Tortoise following case

  1. Create a second little turtle
#include "ros/ros.h"
#include "turtlesim/Spawn.h"
int main(int argc, char** argv)
{
    // Set encoding
    setlocale(LC_ALL,"");
    ros::init(argc,argv,"request_spawn");
    ros::NodeHandle nh;
    // Create client object and publish request
    ros::ServiceClient client_spawn = nh.serviceClient<turtlesim::Spawn>("/spawn");
    // Waiting for requester
    ros::service::waitForService("/spawn");
    // Create location information
    turtlesim::Spawn sp;
    sp.request.name = "turtle2";
    sp.request.x = 1;
    sp.request.y = 1;
    sp.request.theta = 3.14;
    // Publish request
    bool flag = client_spawn.call(sp);
    if(flag)
        ROS_INFO("Created successfully");
    else
        ROS_INFO("Creation failed");
    ros::spin();
    return 0;
}
  1. Publish turtle position information to TF coordinate system
#include "ros/ros.h"
#Include "turnlesim / pose. H" / / location message header file
#include "tf2_ros/transform_broadcaster.h "/ / contains publishing dynamic coordinate relationships
#include "geometry_ Msgs / transformstamped. H "/ / TF coordinate message
#include "tf2/LinearMath/Quaternion.h" / / Euler angle conversion header file
std::string name;
void My_do_thing(const turtlesim::Pose::ConstPtr& msg) {
    // 4. The callback function processes the subscribed message: convert the location image into a relative coordinate relationship and publish it
    // a. Create publishing objects, create static objects
    static tf2_ros::TransformBroadcaster tf_tur;
    // b. Organize and publish data
    geometry_msgs::TransformStamped ts;
    ts.header.stamp = ros::Time::now();
    ts.header.frame_id = "world";    // Base coordinate system
    ts.child_frame_id = name;  // Tortoise coordinate system name
    ts.transform.translation.x = msg->x;
    ts.transform.translation.y = msg->y;
    ts.transform.translation.z = 0;
    // Coordinate system quaternion,
    /* There is no quaternion in the position information, but there is a yaw angle */
    tf2::Quaternion qtn;
    qtn.setRPY(0,0,msg->theta);
    ts.transform.rotation.x = qtn.getX();
    ts.transform.rotation.y = qtn.getY();
    ts.transform.rotation.z = qtn.getZ();
    ts.transform.rotation.w = qtn.getW();
    // c. Publish data
    tf_tur.sendTransform(ts);
}
int main(int argc, char** argv) {
    // 2. Set code, initialization and NodeHandle;
    setlocale(LC_ALL,"");
    ros::init(argc,argv,"send_tf");
    if (argc!=2)
    {
        ROS_ERROR("Parameter error!!!");
    }else{
        name = argv[1];
        ROS_INFO("success.");
    }
    ros::NodeHandle nh;
    ros::Subscriber sub = nh.subscribe<turtlesim::Pose>(name+"/pose",100,My_do_thing);
    // 5. spin();
    ros::spin();
    return 0;
}
  1. Set linear and angular velocity
/*  
    Subscribe to the TF broadcast information of turnle1 and turnle2, find and convert the latest TF information
    Convert turnle1 into coordinates relative to turnle2, calculate the linear velocity and angular velocity and publish them
    Implementation process:
        1.Include header file
        2.Initialize ros node
        3.Create ros handle
        4.Create TF subscription object
        5.Process TF subscribed to
        6.spin
*/
//1. Include header file
#include "ros/ros.h"
#include "tf2_ros/transform_listener.h"
#include "geometry_msgs/TransformStamped.h"
#include "geometry_msgs/Twist.h"

int main(int argc, char *argv[])
{
    setlocale(LC_ALL,"");
    // 2. Initialize ros node
    ros::init(argc,argv,"send_speed");
    // 3. Create ros handle
    ros::NodeHandle nh;
    // 4. Create TF subscription object
    tf2_ros::Buffer buffer;
    tf2_ros::TransformListener listener(buffer);
    // 5. Process TF subscribed to
    // Need to create Publication / turnle2 / CMD_ publisher object for vel
    ros::Publisher pub = nh.advertise<geometry_msgs::Twist>("/turtle2/cmd_vel",1000);
    ros::Rate rate(10);
    while (ros::ok())
    {
        try
        {
            //5-1. First obtain the coordinate information of turnle1 relative to turnle2
            geometry_msgs::TransformStamped tfs = buffer.lookupTransform("turtle2","turtle1",ros::Time(0));

            //5-2. Generate speed information based on coordinate information -- geometry_msgs/Twist.h
            geometry_msgs::Twist twist;
            twist.linear.x = 0.5 * sqrt(pow(tfs.transform.translation.x,2) + pow(tfs.transform.translation.y,2));
            twist.angular.z = 4 * atan2(tfs.transform.translation.y,tfs.transform.translation.x);
            
            //5-3. Publishing speed information -- you need to create a publish object in advance
            pub.publish(twist);
        }
        catch(const std::exception& e)
        {
            // std::cerr << e.what() << '\n';
            ROS_INFO("Error prompt:%s",e.what());
        }
        rate.sleep();
        // 6.spin
        ros::spinOnce();
    }
    return 0;
}

2, rosbag

In the implementation of robot navigation, it may be necessary to draw the global map required for navigation. There are two ways to draw the map. Mode 1: it can control the robot motion, process the data sensed by the robot sensor from time to time, and generate map information. Method 2: also control the robot movement, save the data sensed by the robot sensor, and then re read the data to generate map information. Compared with the two methods, mode 2 is obviously more flexible and convenient.

**Concept: * * a tool for recording and playing back ROS themes.

**Function: * * data reuse to facilitate debugging and testing.

**Essence: * * rosbag is also an ros node in essence. When recording, rosbag is a subscription node that can subscribe to topic messages and write the subscribed data to disk files; When replaying, rosbag is a publishing node, which can read disk files and publish topic messages in files.

1. Command line usage

  1. Create a folder (the folder location is not specially specified, any location can be used) to save the recorded operation
mkdir bags
  1. start recording
rosbag record -a -O ~route/Target file

Operate the little turtle for a period of time, end the recording, and use ctrl + c to generate a bag file in the created directory.

  1. View file information
rosbag info file name
  1. Playback file
rosbag play file name

Restart the tortoise node and you will find that the tortoise moves according to the track at the time of recording.

2. Coding method

  1. Write operation
#include <ros/ros.h>
// Import header file
#include "rosbag/bag.h"
#include "std_msgs/String.h"
int main(int argc, char *argv[]) {
    // Prevent Chinese garbled code
    setlocale(LC_ALL,"");
    ros::init(argc,argv,"demo01_write_bag");
    ros::NodeHandle nh;
    // Create rosbag object
    rosbag::Bag bag;
    // Open file stream
    bag.open("hello.bag",rosbag::BagMode::Write);
    // Write data
    
    std_msgs::String msg;
    msg.data = "hello--->";
    // Parameter 1: topic name, parameter 2: time, parameter 3: message.
    bag.write("/chatter",ros::Time::now(),msg);
    bag.write("/chatter",ros::Time::now(),msg);
    bag.write("/chatter",ros::Time::now(),msg);
    bag.write("/chatter",ros::Time::now(),msg);
    std::cout << msg.data << std::endl;
    ROS_INFO("success");
    // Close file stream
    bag.close();
    return 0;
}
  1. Read operation
#include "ros/ros.h"
#include "rosbag/bag.h"
#include "rosbag/view.h"
#include "std_msgs/String.h"
int main(int argc, char *argv[])
{
    setlocale(LC_ALL,"");
    ros::init(argc,argv,"demo02_read_bag");
    ros::NodeHandle nh;
    // create object
    rosbag::Bag bag;
    // Open package
    bag.open("hello.bag",rosbag::BagMode::Read);
    // Take out the topic, time and object
    // Read data, rosbag::View(bag) iterator
    for(auto &&m : rosbag::View(bag)){
        // m.getTopic() resolve topic
        // ROS_INFO(m.getTopic().c_str());
        std::string topic = m.getTopic();
        // Get timestamp
        ros::Time time = m.getTime();
        // Message value
        std_msgs::StringConstPtr p = m.instantiate<std_msgs::String>();
        ROS_INFO("Content and topic of analysis:%s,Timestamp:%.2f,Message value:%s",
            topic.c_str(),time.toSec(),p->data.c_str());
    }
    // Close package
    bag.close();
    return 0;
}

3, rqt toolbox

1. Installation, startup and basic use

  1. Installation (only if it is not installed)
sudo apt-get install ros-noetic-rqt
sudo apt-get install ros-noetic-rqt-common-plugins
  1. start-up
rqt

2.rqt plug-in: rqt_ Graph (visual display calculation diagram)

**Start: * * you can add it in the plugins of rqt or use rqt_graph start

3.rqt plug-in: rqt_ Console (display and filter logs)

**Start: * * you can add it in the plugins of rqt or use rqt_console startup

4.rqt plug-in: rqt_ Plot (graphic drawing)

**Start: * * you can add it in the plugins of rqt or use rqt_plot start

5.rqt plug-in: rqt_ Bag (record and replay bag files)

**Start: * * you can add it in the plugins of rqt or use rqt_bag start

Operation:

Keywords: C++ ROS Autonomous vehicles

Added by skroks609 on Thu, 02 Sep 2021 01:09:52 +0300