把ros消息转换成中文输出
c++实现
发布
//发布性能评估数据 /trilateration_time_log
void publishTrilaterationLog(
const int reflectorPanelPoints_size,
const double duration_count,
const std::string& resultType,
const std::string& resultChineseMessage,
const std::string& resultENMessage,
const std::string& className,
int classLine,
const int time_log_fig,
const int matchokReflectorPanelPointSize
) {
/*
选择性能评估数据 /trilateration_time_log
int time_log_fig_=-1;
-1:全部关闭,0:全部打开 , -2:只打开 "1:FindCircle拟定圆心坐标,6:匹配算法,9:位姿推算" 3个性能评估数据。
1:FindCircle: 通过雷达强度数据,使用三角函数拟定圆心坐标,并存入反光板数据缓存中
2:匹配数据: 通过得到的圆心坐标,在已经匹配成功的反光板数据缓存中匹配数据
3:匹配数据: 通过得到的圆心坐标,在储存所有的反光板数据缓存中匹配数据
4:匹配数据: 通过得到的圆心坐标,在反光板数据缓存中匹配数据
5:匹配数据: 匹配走广度优先算法 或 匹配走广度优先算法 + 优先使用匹配好的反光板数据
6:匹配算法:从查找圆心到匹配完成需要的总执行时间
7:位姿推算: 基于之前已经匹配上了反光板,推算位姿
8:位姿推算: 经典三边定位最小二乘法,推算位姿
9:位姿推算: 基于之前已经匹配上了反光板 + 经典三边定位最小二乘法,推算位姿
*/
trilateration::trilateration_read_time_log trilateration_read_time_log2;
trilateration_read_time_log2.result_type = resultType;
trilateration_read_time_log2.result_chinese_message = resultChineseMessage;
trilateration_read_time_log2.result_EN_message = resultENMessage;
trilateration_read_time_log2.className = className;
trilateration_read_time_log2.classLine = classLine;
trilateration_read_time_log2.num_points = reflectorPanelPoints_size;
trilateration_read_time_log2.execution_time = duration_count;
trilateration_read_time_log2.time_log_fig=time_log_fig;
trilateration_read_time_log2.matchokReflectorPanelPointSize=matchokReflectorPanelPointSize;//队列数量
time_log_pub_.publish(trilateration_read_time_log2);
}
//发布性能评估数据 10:位姿推算: 所有使用默认的 tf_last_odom_to_map_transform_ 数据 发布的移动机器人坐标
if(time_log_fig_==0||time_log_fig_==10) {//-1:全部关闭,0:全部打开 , -2:只打开 "1:FindCircle拟定圆心坐标,6:匹配算法,9:位姿推算" 3个性能评估数据。 ,1:打开第一个,2:打开第二个 3:.....
std::string resultType = "trilateration_execution";
std::string resultChineseMessage = " 使用上一次 mapTodom -> tf_last_odom_to_map_transform_ 的tf数据,发布移动机器人的位置坐标。[mutex]";
std::string resultENMessage = "Use the previous mapTodom ->tf_1ast_odom_to-map_transform_ tf data to publish the position coordinates of the mobile robot. [mutex]";
std::string className = __FILE__; // 更改为实际的文件名
int classLine = __LINE__; // 更改为实际的行号
///trilateration_time_log
publishTrilaterationLog(0, duration.count(), resultType, resultChineseMessage, resultENMessage, className, classLine,time_log_fig_,matchokReflectorPanelPoint_.size());
}
接收 【重点看接收转码】
#include "ros/ros.h"
#include "trilateration/trilateration_read_time_log.h"
#include <locale>
#include <codecvt>
#include <string>
#include <sstream>
// 将 Unicode 转义字符串解码为 UTF-8 编码的中文字符串
std::string decodeUnicodeString(const std::string& unicode_string)
{
std::string decoded_string;
size_t pos = 0;
size_t last_pos = 0;
while ((pos = unicode_string.find("\\u", last_pos)) != std::string::npos) {
decoded_string.append(unicode_string, last_pos, pos - last_pos);
std::string hex_code = unicode_string.substr(pos + 2, 4);
unsigned int code_point;
std::stringstream ss;
ss << std::hex << hex_code;
ss >> code_point;
char utf8_char[5] = {0};
if (code_point <= 0x7F) {
utf8_char[0] = code_point;
} else if (code_point <= 0x7FF) {
utf8_char[0] = 0xC0 | (code_point >> 6);
utf8_char[1] = 0x80 | (code_point & 0x3F);
} else if (code_point <= 0xFFFF) {
utf8_char[0] = 0xE0 | (code_point >> 12);
utf8_char[1] = 0x80 | ((code_point >> 6) & 0x3F);
utf8_char[2] = 0x80 | (code_point & 0x3F);
} else {
utf8_char[0] = 0xF0 | (code_point >> 18);
utf8_char[1] = 0x80 | ((code_point >> 12) & 0x3F);
utf8_char[2] = 0x80 | ((code_point >> 6) & 0x3F);
utf8_char[3] = 0x80 | (code_point & 0x3F);
}
decoded_string += std::string(utf8_char);
last_pos = pos + 6;
}
decoded_string.append(unicode_string, last_pos);
return decoded_string;
}
// 订阅的回调函数
void chatterCallback(const trilateration::trilateration_read_time_log::ConstPtr& msg)
{
// 将 Unicode 转义字符串解码为中文字符串
std::string decoded_chinese_message = decodeUnicodeString(msg->result_chinese_message);
// 输出所有字段的数据
ROS_INFO("Time Log Fig: %d", msg->time_log_fig);
ROS_INFO("Result Type: %s", msg->result_type.c_str());
ROS_INFO("Class Name: %s", msg->className.c_str());
ROS_INFO("Class Line: %d", msg->classLine);
ROS_INFO("Decoded Chinese Message: %s", decoded_chinese_message.c_str());
ROS_INFO("English Message: %s", msg->result_EN_message.c_str());
ROS_INFO("Result Message: %s", msg->result_message.c_str());
ROS_INFO("Number of Points: %d", msg->num_points);
ROS_INFO("Match OK Reflector Panel Point Size: %d", msg->matchokReflectorPanelPointSize);
ROS_INFO("Execution Time: %s", msg->execution_time.c_str());
}
int main(int argc, char **argv)
{
// setlocale(LC_ALL, ""); //中文
setlocale(LC_CTYPE,"zh_CN.utf8");
ros::init(argc, argv, "listener");
ros::NodeHandle n;
ros::Subscriber sub = n.subscribe("/trilateration_time_log", 1000, chatterCallback);
ros::spin();
return 0;
}
python实现
import json
unicode_string = r"\u901A\u8FC7\u96F7\u8FBE\u5F3A\u5EA6\u6570\u636E\uFF0C\u5E76\u5B58\u5165\u53CD\u5149\u677F\u6570\u636E\u7F13\u5B58\u4E2D"
decoded_string = unicode_string.encode().decode('unicode_escape')
print(decoded_string)
控制台输出结果: