浏览器及java读取ros1的topic
// 获取雷达数据
rostopic echo /scan
(1)法1:
maven setting依赖修改依赖修改
<mirror><id>aliyunmaven</id><mirrorOf>*,!rosjava-mvn-repo</mirrorOf><name>阿里云公共仓库</name><url>https://maven.aliyun.com/repository/public</url></mirror><mirror><id>nexus</id><mirrorOf>*,!rosjava-mvn-repo</mirrorOf><name>nexus public</name><url>http://192.168.2.220:8081/repository/maven-public</url></mirror><!-- 添加 ROS Java 仓库的镜像配置 --><mirror><id>rosjava-mvn-repo</id><mirrorOf>rosjava-mvn-repo</mirrorOf><name>ROS Java Maven Repository</name><url>https://raw.githubusercontent.com/rosjava/rosjava_mvn_repo/master/</url></mirror></mirrors>
maven依赖添加 pom.xml
<?xml version="1.0" encoding="UTF-8"?>
<project xmlns="http://maven.apache.org/POM/4.0.0"xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"xsi:schemaLocation="http://maven.apache.org/POM/4.0.0 http://maven.apache.org/xsd/maven-4.0.0.xsd"><modelVersion>4.0.0</modelVersion><groupId>org.example</groupId><artifactId>java_ros</artifactId><version>1.0-SNAPSHOT</version><properties><maven.compiler.source>17</maven.compiler.source><maven.compiler.target>17</maven.compiler.target><project.build.sourceEncoding>UTF-8</project.build.sourceEncoding></properties><dependencies><dependency><groupId>org.ros.rosjava_core</groupId><artifactId>rosjava</artifactId><version>0.3.6</version></dependency><dependency><groupId>org.ros.rosjava_messages</groupId><artifactId>std_msgs</artifactId><version>0.5.8</version></dependency><dependency><groupId>org.ros.rosjava_messages</groupId><artifactId>sensor_msgs</artifactId><version>1.12.7</version></dependency><!-- 添加WebSocket客户端依赖用于连接rosbridge --><dependency><groupId>org.java-websocket</groupId><artifactId>Java-WebSocket</artifactId><version>1.5.3</version></dependency></dependencies><repositories><!-- ROS Java 仓库 --><repository><id>rosjava-mvn-repo</id><name>ROS Java Maven Repository</name><url>https://raw.githubusercontent.com/rosjava/rosjava_mvn_repo/master/</url><releases><enabled>true</enabled></releases><snapshots><enabled>false</enabled></snapshots></repository></repositories><pluginRepositories><pluginRepository><id>rosjava-mvn-repo</id><name>ROS Java Maven Repository</name><url>https://raw.githubusercontent.com/rosjava/rosjava_mvn_repo/master/</url><releases><enabled>true</enabled></releases><snapshots><enabled>false</enabled></snapshots></pluginRepository></pluginRepositories></project>
3.读取topic代码 读取的topic为/scan
package ros;import org.ros.message.MessageListener;
import org.ros.namespace.GraphName;
import org.ros.node.*;
import org.ros.node.topic.Subscriber;
import sensor_msgs.LaserScan;import java.net.URI;
import java.util.List;
/*** 订阅激光扫描数据* 示例1*/
public class LaserScanSubscriber extends AbstractNodeMain {@Overridepublic GraphName getDefaultNodeName() {return GraphName.of("laser_scan_subscriber");}@Overridepublic void onStart(ConnectedNode connectedNode) {// 创建订阅者,订阅/scan话题,消息类型为sensor_msgs/LaserScanSubscriber<LaserScan> subscriber = connectedNode.newSubscriber("/scan", LaserScan._TYPE);// 添加消息监听器subscriber.addMessageListener(new MessageListener<LaserScan>() {@Overridepublic void onNewMessage(LaserScan message) {System.out.println("=====================================");System.out.println("Received laser scan message:");System.out.println("Header: " + message.getHeader());System.out.println("Angle min: " + message.getAngleMin());System.out.println("Angle max: " + message.getAngleMax());System.out.println("Angle increment: " + message.getAngleIncrement());System.out.println("Time increment: " + message.getTimeIncrement());System.out.println("Scan time: " + message.getScanTime());System.out.println("Range min: " + message.getRangeMin());System.out.println("Range max: " + message.getRangeMax());// 打印部分距离数据float[] ranges = message.getRanges();System.out.println("Number of range points: " + ranges.length);System.out.print("First 10 range values: ");for (int i = 0; i < Math.min(10, ranges.length); i++) {System.out.print(ranges[i] + " ");}System.out.println();// 如果有强度数据,也打印部分float[] intensities = message.getIntensities();if (intensities.length > 0) {System.out.print("First 10 intensity values: ");for (int i = 0; i < Math.min(10, intensities.length); i++) {System.out.print(intensities.length + " ");}System.out.println();}}});}public static void main(String[] args) {// 创建节点配置NodeConfiguration nodeConfiguration = NodeConfiguration.newPublic("192.168.209.100", URI.create("http://192.168.209.100:11311"));// 创建节点执行器
// NodeMainExecutor nodeMainExecutor = NodeMainExecutor.newDefault();NodeMainExecutor nodeMainExecutor = DefaultNodeMainExecutor.newDefault();// 创建并运行订阅者节点LaserScanSubscriber subscriberNode = new LaserScanSubscriber();nodeMainExecutor.execute(subscriberNode, nodeConfiguration);System.out.println("LaserScan subscriber started. Listening to /scan topic...");System.out.println("Press Ctrl+C to stop.");}
}
跳过证书直接安装robridge
sudo apt-get install ros-<your_ros_distro>-rosbridge-suite
证书跳过安装
sudo apt-get -o Acquire::https::Verify-Peer=false install ros-noetic-rosbridge-suite
//启动ubuntu的
roslaunch rosbridge_server rosbridge_websocket.launch
//使用rviz_vue显示
https://github.com/BySlin/web_rviz_demo/tree/main
sudo apt install -o Acquire::https::Verify-Peer=false ros-$ROS_DISTRO-foxglove-bridge
roslaunch --screen foxglove_bridge foxglove_bridge.launch port:=8765