码迷,mamicode.com
首页 > 移动开发 > 详细

ros和Android(一)

时间:2016-08-19 23:47:19      阅读:1927      评论:0      收藏:0      [点我收藏+]

标签:

ros和Android

ros基本要素:

1.节点 :节点与节点用tcp/ip通信
2.节点管理器 :(相当于域名解析器)所有节点的枢纽,节点之间要实现互相通信,都要通过节点管理器
3.消息 :
4.参数服务器  :
5.主题 :某一类的节点通信 例如:scan主题,所有扫描的订阅和发布都可以放在这个主题上
6.服务 :
7.消息记录包:
8.订阅:
9.发布:
 
 
c++中的例子提取出的步骤
1.创建消息和服务:
消息文件(.msg)一般带Header+基本类型数据+消息文件类型
服务文件(.srv)请求+响应 ---划分,请求,响应也是由基本类型组成
 
 
  1. 4// This header defines the standard ROS classes .
  2. 5#include<ros / ros.h>
  3. 6
  4. 7int main (int argc ,char** argv ){
  5. 8// Initialize the ROS system .
  6. 9 ros::init ( argc , argv ," hello _ros ");
  7. 10
  8. 11// Establ ish this program as a ROS node .
  9. 12 ros::NodeHandle nh ;
  10. 13
  11. 14// Send some output as a log message .
  12. 15 ROS_INFO_STREAM(" Hello , ? ROS! ");
  13. 16}
 
c++发布订阅端程序
  1. 1// This program publishes randomly−generated velocity
  2. 2// messages for turtlesim .
  3. 3#include<ros / ros.h>
  4. 4#include<geometry_msgs /Twist. h>// For geometry_msgs:: Twist
  5. 5#include<stdlib.h>// For rand() and RAND_MAX
  6. 6
  7. 7int main (int argc ,char** argv ){
  8. 8// Initialize the ROS system and become a node .
  9. 9 ros::init ( argc , argv ," publish _ velocity ");
  10. 10 ros::NodeHandle nh ;
  11. 11
  12. 12// Create a publisher obj ect .
  13. 13 ros::Publisher pub = nh . advertise <geometry_msgs::Twist>(
  14. 14" turtle1 /cmd_vel",1000);
  15. 15
  16. 16// Seed the random number generator .
  17. 17 srand ( time (0));
  18. 18
  19. 19// Loop at 2Hz until the node is shut down.
  20. 20 ros::Raterate(2);
  21. 21while( ros::ok ()){
  22. 22// Create and fill in the message . The other four
  23. 23// fields , which are ignored by turtl esim , default to 0.
  24. 24 geometry_msgs ::Twist msg ;
  25. 25 msg . linear . x =double( rand ())/double(RAND_MAX);
  26. 26 msg.angular.z =2*double( rand ())/double(RAND_MAX)1;
  27. 27
  28. 28// Publish the message .
  29. 29 pub . publish ( msg );
  30. 30
  31. 31// Send a message to rosout with the details .
  32. 32 ROS_INFO_STREAM("Sending random velocity command : "
  33. 33<<" linear="<< msg.linear.x
  34. 34<<" angular="<< msg.angular.z);
  35. 35
  36. 36// Wait untilit‘s time for another iteration .
  37. 37 rate.sleep ();
  38. 38}
  39. 39}
  40. 3
订阅者的程序
  1. 1// This program subscribes to turtle1/pose and shows its
  2. 2// messages on the screen .
  3. 3#include<ros / ros.h>
  4. 4#include<turtlesim /Pose.h>
  5. 5#include<iomanip>// for std::setprecision and std::fixed
  6. 6
  7. 7// A callback function . Executed each time a new pose
  8. 8// message arrives .
  9. 9void poseMessageReceived (const turtlesim::Pose& msg ){
  10. 10 ROS_INFO_STREAM( std::setprecision (2)<< std::fixed
  11. 11<<" position =("<< msg . x <<" , "<< msg . y <<" ) "
  12. 12<<" *direction="<< msg . theta );
  13. 13}
  14. 14
  15. 15int main (int argc ,char** argv ){
  16. 16// Initialize the ROS system and become a node .
  17. 17 ros::init ( argc , argv ," subscribe_to _pose ");
  18. 18 ros::NodeHandle nh ;
  19. 19
  20. 20// Create a subscri ber obj ect .
  21. 21 ros::Subscriber sub = nh.subscribe (" turtle1/pose ",1000,
  22. 22&poseMessageReceived );
  23. 23
  24. 24// Let ROS take over .
  25. 25 ros::spin ();
  26. 26}
 
 
 
 

rosjava发布者的一般写法

  1. /**
  2. * Publisher必须继承NodeMain  重写NodeMain的getDefaultNodeName()
  3. */
  4. publicclassImuPublisherimplementsNodeMain
  5. {
  6. privateImuThread imuThread;
  7. privateSensorListener sensorListener;
  8. privateSensorManager sensorManager;
  9. privatePublisher<Imu> publisher;
  10. privateclassImuThreadextendsThread
  11. {
  12. privatefinalSensorManager sensorManager;
  13. privateSensorListener sensorListener;
  14. privateLooper threadLooper;
  15. privatefinalSensor accelSensor;
  16. privatefinalSensor gyroSensor;
  17. privatefinalSensor quatSensor;
  18. privateImuThread(SensorManager sensorManager,SensorListener sensorListener)
  19. {
  20. this.sensorManager = sensorManager;
  21. this.sensorListener = sensorListener;
  22. this.accelSensor =this.sensorManager.getDefaultSensor(Sensor.TYPE_ACCELEROMETER);
  23. this.gyroSensor =this.sensorManager.getDefaultSensor(Sensor.TYPE_GYROSCOPE);
  24. this.quatSensor =this.sensorManager.getDefaultSensor(Sensor.TYPE_ROTATION_VECTOR);
  25. }
  26. publicvoid run()
  27. {
  28. Looper.prepare();
  29. this.threadLooper =Looper.myLooper();
  30. this.sensorManager.registerListener(this.sensorListener,this.accelSensor,SensorManager.SENSOR_DELAY_FASTEST);
  31. this.sensorManager.registerListener(this.sensorListener,this.gyroSensor,SensorManager.SENSOR_DELAY_FASTEST);
  32. this.sensorManager.registerListener(this.sensorListener,this.quatSensor,SensorManager.SENSOR_DELAY_FASTEST);
  33. Looper.loop();
  34. }
  35. publicvoid shutdown()
  36. {
  37. this.sensorManager.unregisterListener(this.sensorListener);
  38. if(this.threadLooper !=null)
  39. {
  40. this.threadLooper.quit();
  41. }
  42. }
  43. }
  44. privateclassSensorListenerimplementsSensorEventListener
  45. {
  46. privatePublisher<Imu> publisher;
  47. privateImu imu;
  48. privateSensorListener(Publisher<Imu> publisher,boolean hasAccel,boolean hasGyro,boolean hasQuat)
  49. {
  50. this.publisher = publisher;
  51. ...
  52. this.imu =this.publisher.newMessage();
  53. }
  54. // @Override
  55. publicvoid onSensorChanged(SensorEvent event)
  56. {
  57. this.imu.getLinearAcceleration().setX(event.values[0]);
  58. this.imu.getLinearAcceleration().setY(event.values[1]);
  59. this.imu.getLinearAcceleration().setZ(event.values[2]);
  60. this.imu.setLinearAccelerationCovariance(tmpCov);
  61. this.imu.getAngularVelocity().setX(event.values[0]);
  62. this.imu.getAngularVelocity().setY(event.values[1]);
  63. this.imu.getAngularVelocity().setZ(event.values[2]);
  64. double[] tmpCov ={0.0025,0,0,0,0.0025,0,0,0,0.0025};// TODO Make Parameter
  65. this.imu.setAngularVelocityCovariance(tmpCov);
  66. this.imu.getOrientation().setW(quaternion[0]);
  67. this.imu.getOrientation().setX(quaternion[1]);
  68. this.imu.getOrientation().setY(quaternion[2]);
  69. this.imu.getOrientation().setZ(quaternion[3]);
  70. double[] tmpCov ={0.001,0,0,0,0.001,0,0,0,0.001};// TODO Make Parameter
  71. this.imu.setOrientationCovariance(tmpCov);
  72. //组装header
  73. // Convert event.timestamp (nanoseconds uptime) into system time, use that as the header stamp
  74. long time_delta_millis =System.currentTimeMillis()-SystemClock.uptimeMillis();
  75. this.imu.getHeader().setStamp(Time.fromMillis(time_delta_millis + event.timestamp/1000000));
  76. this.imu.getHeader().setFrameId("/imu");// TODO Make parameter
  77. //前面组装消息
  78.  
  79. //后面发布消息
  80. publisher.publish(this.imu);
  81. // Create a new message ,清空了this.imu
  82. this.imu =this.publisher.newMessage();
  83. // Reset times
  84. this.accelTime =0;
  85. this.gyroTime =0;
  86. this.quatTime =0;
  87. }
  88. }
  89. }
  90. publicImuPublisher(SensorManager manager)
  91. {
  92. this.sensorManager = manager;
  93. }
  94. publicGraphName getDefaultNodeName()
  95. //节点名称
  96. returnGraphName.of("android_sensors_driver/imuPublisher");
  97. }
  98. publicvoid onError(Node node,Throwable throwable)
  99. {
  100. }
  101. publicvoid onStart(ConnectedNode node)
  102. {
  103. try
  104. {
  105. //主题为"android/imu" 消息类型为 "sensor_msgs/Imu" ,是标准类型的消息
  106. this.publisher = node.newPublisher("android/imu","sensor_msgs/Imu");
  107.    ......
  108. this.sensorListener = new SensorListener(publisher, hasAccel, hasGyro, hasQuat);
  109. this.imuThread.start();   
  110. this.imuThread = new ImuThread(this.sensorManager, sensorListener);
  111. }
  112. catch(Exception e)
  113. {
  114. if(node !=null)
  115. {
  116. node.getLog().fatal(e);
  117. }
  118. else
  119. {
  120. e.printStackTrace();
  121. }
  122. }
  123. }
  124. //@Override
  125. publicvoid onShutdown(Node arg0)
  126. {
  127. ....
  128. }
  129. //@Override
  130. publicvoid onShutdownComplete(Node arg0)
  131. {
  132. }
  133. }
其中NodeMain 必须重写getDefaultNodeName()节点名称
  1. publicinterfaceNodeMainextendsNodeListener{
  2. GraphName getDefaultNodeName();
  3. }
消息使用的是是Rosjava库里面预值好的一个格式
  1. //
  2. // Source code recreated from a .class file by IntelliJ IDEA
  3. // (powered by Fernflower decompiler)
  4. //
  5. package sensor_msgs;
  6. import geometry_msgs.Quaternion;
  7. import geometry_msgs.Vector3;
  8. import org.ros.internal.message.Message;
  9. import std_msgs.Header;
  10. publicinterfaceImuextendsMessage{
  11. String _TYPE ="sensor_msgs/Imu";
  12. String _DEFINITION ="# This is a message to hold data from an IMU (Inertial Measurement Unit)\n#\n# Accelerations should be in m/s^2 (not in g\‘s), and rotational velocity should be in rad/sec\n#\n# If the covariance of the measurement is known, it should be filled in (if all you know is the \n# variance of each measurement, e.g. from the datasheet, just put those along the diagonal)\n# A covariance matrix of all zeros will be interpreted as \"covariance unknown\", and to use the\n# data a covariance will have to be assumed or gotten from some other source\n#\n# If you have no estimate for one of the data elements (e.g. your IMU doesn\‘t produce an orientation \n# estimate), please set element 0 of the associated covariance matrix to -1\n# If you are interpreting this message, please check for a value of -1 in the first element of each \n# covariance matrix, and disregard the associated estimate.\n\nHeader header\n\ngeometry_msgs/Quaternion orientation\nfloat64[9] orientation_covariance # Row major about x, y, z axes\n\ngeometry_msgs/Vector3 angular_velocity\nfloat64[9] angular_velocity_covariance # Row major about x, y, z axes\n\ngeometry_msgs/Vector3 linear_acceleration\nfloat64[9] linear_acceleration_covariance # Row major x, y z \n";
  13. Header getHeader();
  14. void setHeader(Header var1);
  15. Quaternion getOrientation();
  16. void setOrientation(Quaternion var1);
  17. double[] getOrientationCovariance();
  18. void setOrientationCovariance(double[] var1);
  19. Vector3 getAngularVelocity();
  20. void setAngularVelocity(Vector3 var1);
  21. double[] getAngularVelocityCovariance();
  22. void setAngularVelocityCovariance(double[] var1);
  23. Vector3 getLinearAcceleration();
  24. void setLinearAcceleration(Vector3 var1);
  25. double[] getLinearAccelerationCovariance();
  26. void setLinearAccelerationCovariance(double[] var1);
  27. }

rosjava发布者的使用

 
XActivity .java
  1. publicclass XActivityextendsRosActivity
  2. {
  3. privateImuPublisher imu_pub;
  4. privateSensorManager mSensorManager;
  5. public XActivity()
  6. {
  7. super("Ros Android Sensors Driver","Ros Android Sensors Driver");
  8. }
  9. @Override
  10. protectedvoid onCreate(Bundle savedInstanceState)
  11. {
  12. super.onCreate(savedInstanceState);
  13. setContentView(R.layout.main);
  14. mSensorManager =(SensorManager)this.getSystemService(SENSOR_SERVICE);
  15. }
  16. @Override
  17. protectedvoid onResume()
  18. {
  19. super.onResume();
  20. }
  21. @Override
  22. protectedvoid init(NodeMainExecutor nodeMainExecutor)
  23. {
  24. NodeConfiguration nodeConfiguration3 =NodeConfiguration.newPublic(InetAddressFactory.newNonLoopback().getHostAddress());
  25. nodeConfiguration3.setMasterUri(getMasterUri());
  26. nodeConfiguration3.setNodeName("android_sensors_driver_imu");
  27. this.imu_pub =newImuPublisher(mSensorManager);
  28. nodeMainExecutor.execute(this.imu_pub, nodeConfiguration3);
  29. }
  30. }
其中的 nodeConfiguration3.setNodeName("android_sensors_driver_imu");
觉得很奇怪,在ImuPublisher中已经设置了节点名称,到底是谁在起作用呢?
 
ImuPublisher.java
  1. publicGraphName getDefaultNodeName()
  2. {
  3. //节点名称
  4. returnGraphName.of("android_sensors_driver/imuPublisher");
  5. }
需要跟踪 nodeMainExecutor.execute(this.imu_pub, nodeConfiguration3);方法
 
XActivity .java
  1. @Override
  2. protectedvoid init(NodeMainExecutor nodeMainExecutor)
  3. {
  4. ...
  5. }
是从父类继承过来的,父类再启动中会startServic
 
RosActivity.java
  1. protectedRosActivity(String notificationTicker,String notificationTitle, URI customMasterUri){
  2. super();
  3. this.notificationTicker = notificationTicker;
  4. this.notificationTitle = notificationTitle;
  5. nodeMainExecutorServiceConnection =newNodeMainExecutorServiceConnection(customMasterUri);
  6. }
  7. @Override
  8. protectedvoid onStart(){
  9. super.onStart();
  10. bindNodeMainExecutorService();//启动service
  11. }
  12. //startService+bindService
  13. //如果我们想保持和 Service 的通信,又不想让 Service 随着 Activity 退出而退出呢?你可以先 startService() 然后再 bindService() 。
  14. //当你不需要绑定的时候就执行 unbindService() 方法,执行这个方法只会触发 Service 的 onUnbind() 而不会把这个 Service 销毁。
  15. //这样就可以既保持和 Service 的通信,也不会随着 Activity 销毁而销毁了
  16. protectedvoid bindNodeMainExecutorService(){
  17. Intent intent =newIntent(this,NodeMainExecutorService.class);
  18. intent.setAction(NodeMainExecutorService.ACTION_START);
  19. intent.putExtra(NodeMainExecutorService.EXTRA_NOTIFICATION_TICKER, notificationTicker);
  20. intent.putExtra(NodeMainExecutorService.EXTRA_NOTIFICATION_TITLE, notificationTitle);
  21. startService(intent);//启动服务
  22. Preconditions.checkState(
  23. bindService(intent, nodeMainExecutorServiceConnection, BIND_AUTO_CREATE),//绑定连接状态回调
  24. "Failed to bind NodeMainExecutorService.");
  25. }
这个servic连接上的时候会回调,回调会取出binder,((NodeMainExecutorService.LocalBinder) binder).getService()得到nodeMainExecutorService 然后init();
 
RosActivity.java
  1. privatefinalclassNodeMainExecutorServiceConnectionimplementsServiceConnection{
  2. private URI customMasterUri;
  3. publicNodeMainExecutorServiceConnection(URI customUri){
  4. super();
  5. customMasterUri = customUri;
  6. }
  7. @Override
  8. publicvoid onServiceConnected(ComponentName name,IBinder binder){
  9. nodeMainExecutorService =((NodeMainExecutorService.LocalBinder) binder).getService();//取出发布的操作类
  10. if(customMasterUri !=null){
  11. nodeMainExecutorService.setMasterUri(customMasterUri);
  12. nodeMainExecutorService.setRosHostname(getDefaultHostAddress());
  13. }
  14. nodeMainExecutorService.addListener(newNodeMainExecutorServiceListener(){
  15. @Override
  16. publicvoid onShutdown(NodeMainExecutorService nodeMainExecutorService){
  17. // We may have added multiple shutdown listeners and we only want to
  18. // call finish() once.
  19. if(!RosActivity.this.isFinishing()){
  20. RosActivity.this.finish();
  21. }
  22. }
  23. });
  24. if(getMasterUri()==null){
  25. startMasterChooser();
  26. }else{
  27. init();
  28. }
  29. }
  30. @Override
  31. publicvoid onServiceDisconnected(ComponentName name){
  32. }
  33. };
init()里面就把nodeMainExecutorService传到了子类,子类(执行发布操作的类) 拿到 nodeMainExecutor并执行nodeMainExecutor.execute(this.imu_pub, nodeConfiguration3);
 
RosActivity.java
  1. protectedvoid init(){
  2. // Run init() in a new thread as a convenience since it often requires
  3. // network access.
  4. newAsyncTask<Void,Void,Void>(){
  5. @Override
  6. protectedVoid doInBackground(Void... params){
  7. RosActivity.this.init(nodeMainExecutorService);//调子类的方法,传递发布的操作类
  8. returnnull;
  9. }
  10. }.execute();
  11. }
所以要去查nodeMainExecutor的来源,就要找到启动的service :NodeMainExecutorService
nodeMainExecutor.execute(this.imu_pub, nodeConfiguration3);调用了如下代码
 
NodeMainExecutorService.java
  1. @Override
  2. publicvoid execute(NodeMain nodeMain,NodeConfiguration nodeConfiguration,
  3. Collection<NodeListener> nodeListeneners){
  4. nodeMainExecutor.execute(nodeMain, nodeConfiguration, nodeListeneners);//主界面调用的execute到了这里
  5. }
  6. @Override
  7. publicvoid execute(NodeMain nodeMain,NodeConfiguration nodeConfiguration){
  8. execute(nodeMain, nodeConfiguration,null);
  9. }
其中的nodeMainExecutor在构造NodeMainExecutorService的时候就初始化了
 
NodeMainExecutorService.java
  1. publicNodeMainExecutorService(){
  2. super();
  3. rosHostname =null;
  4. nodeMainExecutor =DefaultNodeMainExecutor.newDefault();//初始化
  5. binder =newLocalBinder();
  6. listeners =
  7. newListenerGroup<NodeMainExecutorServiceListener>(
  8. nodeMainExecutor.getScheduledExecutorService());
  9. }
查看DefaultNodeMainExecutor.newDefault()是如何初始化的
 
  1. publicstaticNodeMainExecutor newDefault(){
  2. return newDefault(newDefaultScheduledExecutorService());
  3. }
  4. publicstaticNodeMainExecutor newDefault(ScheduledExecutorService executorService){
  5. returnnewDefaultNodeMainExecutor(newDefaultNodeFactory(executorService), executorService);
  6. }
  7. //真实的初始化执行发布的操作类
  8. privateDefaultNodeMainExecutor(NodeFactory nodeFactory,ScheduledExecutorService scheduledExecutorService){
  9. this.nodeFactory = nodeFactory;
  10. this.scheduledExecutorService = scheduledExecutorService;
  11. this.connectedNodes =Multimaps.synchronizedMultimap(HashMultimap.create());
  12. this.nodeMains =Maps.synchronizedBiMap(HashBiMap.create());
  13. Runtime.getRuntime().addShutdownHook(newThread(newRunnable(){
  14. publicvoid run(){
  15. DefaultNodeMainExecutor.this.shutdown();
  16. }
  17. }));
  18. }
实际的执行代码
  1. publicvoid execute(finalNodeMain nodeMain,NodeConfiguration nodeConfiguration,finalCollection<NodeListener> nodeListeners){
  2. finalNodeConfiguration nodeConfigurationCopy =NodeConfiguration.copyOf(nodeConfiguration);
  3. nodeConfigurationCopy.setDefaultNodeName(nodeMain.getDefaultNodeName());
  4. Preconditions.checkNotNull(nodeConfigurationCopy.getNodeName(),"Node name not specified.");
  5. this.scheduledExecutorService.execute(newRunnable(){
  6. publicvoid run(){
  7. ArrayList nodeListenersCopy =Lists.newArrayList();
  8. nodeListenersCopy.add(DefaultNodeMainExecutor.this.newRegistrationListener(null));
  9. nodeListenersCopy.add(nodeMain);
  10. if(nodeListeners !=null){
  11. nodeListenersCopy.addAll(nodeListeners);
  12. }
  13. Node node =DefaultNodeMainExecutor.this.nodeFactory.newNode(nodeConfigurationCopy, nodeListenersCopy);
  14. DefaultNodeMainExecutor.this.nodeMains.put(node, nodeMain);
  15. }
  16. });
  17. }
nodeConfigurationCopy.setDefaultNodeName(nodeMain.getDefaultNodeName());
如果前台没配置节点名,就会用发布者默认的名称,
如果前台有,就使用前台的名字作为节点名字
 
NodeConfiguration.java
  1. publicNodeConfiguration setDefaultNodeName(GraphName nodeName){
  2. if(this.nodeName ==null){
  3. this.setNodeName(nodeName);
  4. }
  5. returnthis;
  6. }
 
实际上只执行一句DefaultNodeMainExecutor.this.nodeMains.put(node, nodeMain);
node是由前台的节点配置信息和两个监听实例(一个是本页面的,一个发布者的)构造的
  1. Node node =DefaultNodeMainExecutor.this.nodeFactory.newNode(nodeConfigurationCopy, nodeListenersCopy);
构造里面做的事
 
DefaultNodeFactory.java
  1. publicclassDefaultNodeFactoryimplementsNodeFactory{
  2. privatefinalScheduledExecutorService scheduledExecutorService;
  3. publicDefaultNodeFactory(ScheduledExecutorService scheduledExecutorService){
  4. this.scheduledExecutorService =newSharedScheduledExecutorService(scheduledExecutorService);
  5. }
  6. publicNode newNode(NodeConfiguration nodeConfiguration,Collection<NodeListener> listeners){
  7. returnnewDefaultNode(nodeConfiguration, listeners,this.scheduledExecutorService);
  8. }
  9. publicNode newNode(NodeConfiguration nodeConfiguration){
  10. returnthis.newNode(nodeConfiguration,(Collection)null);
  11. }
  12. }
  1. DefaultNode.java
  2.  
  3. publicDefaultNode(NodeConfiguration nodeConfiguration,Collection<NodeListener> nodeListeners,ScheduledExecutorService scheduledExecutorService){
  4. this.nodeConfiguration =NodeConfiguration.copyOf(nodeConfiguration);
  5. this.nodeListeners =newListenerGroup(scheduledExecutorService);
  6. this.nodeListeners.addAll(nodeListeners);
  7. this.scheduledExecutorService = scheduledExecutorService;
  8. this.masterUri = nodeConfiguration.getMasterUri();
  9. this.masterClient =newMasterClient(this.masterUri);
  10. this.topicParticipantManager =newTopicParticipantManager();
  11. this.serviceManager =newServiceManager();
  12. this.parameterManager =newParameterManager(scheduledExecutorService);
  13. GraphName basename = nodeConfiguration.getNodeName();
  14. NameResolver parentResolver = nodeConfiguration.getParentResolver();
  15. this.nodeName = parentResolver.getNamespace().join(basename);
  16. this.resolver =newNodeNameResolver(this.nodeName, parentResolver);
  17. this.slaveServer =newSlaveServer(this.nodeName, nodeConfiguration.getTcpRosBindAddress(), nodeConfiguration.getTcpRosAdvertiseAddress(),
  18. nodeConfiguration.getXmlRpcBindAddress(), nodeConfiguration.getXmlRpcAdvertiseAddress(),this.masterClient,this.topicParticipantManager,
  19. this.serviceManager,this.parameterManager, scheduledExecutorService);
  20. //nodeConfiguration.getTcpRosBindAddress()默认情况下端口为0
  21. //nodeConfiguration.getTcpRosAdvertiseAddress()主界面组装时候配置的host(String)组成的TcpRosAdvertiseAddress
  22. //nodeConfiguration.getXmlRpcBindAddress() 默认情况下端口为0
  23. //nodeConfiguration.getXmlRpcAdvertiseAddress()
  24. this.slaveServer.start();
  25. NodeIdentifier nodeIdentifier =this.slaveServer.toNodeIdentifier();
  26. this.parameterTree =DefaultParameterTree.newFromNodeIdentifier(nodeIdentifier,this.masterClient.getRemoteUri(),this.resolver,this.parameterManager);
  27. this.publisherFactory =newPublisherFactory(nodeIdentifier,this.topicParticipantManager, nodeConfiguration.getTopicMessageFactory(), scheduledExecutorService);
  28. this.subscriberFactory =newSubscriberFactory(nodeIdentifier,this.topicParticipantManager, scheduledExecutorService);
  29. this.serviceFactory =newServiceFactory(this.nodeName,this.slaveServer,this.serviceManager, scheduledExecutorService);
  30. this.registrar =newRegistrar(this.masterClient, scheduledExecutorService);
  31. this.topicParticipantManager.setListener(this.registrar);
  32. this.serviceManager.setListener(this.registrar);
  33. scheduledExecutorService.execute(newRunnable(){
  34. publicvoid run(){
  35. DefaultNode.this.start();
  36. }
  37. });
  38. }
其中this.masterClient =newMasterClient(this.masterUri);配置服务端的地址
  1. publicClient(URI uri,Class<T> interfaceClass){
  2. this.uri = uri;
  3. XmlRpcClientConfigImpl config =newXmlRpcClientConfigImpl();
  4. try{
  5. config.setServerURL(uri.toURL());
 
 
 
 
前台的节点配置信息
  1. NodeConfiguration nodeConfiguration3 =NodeConfiguration.newPublic(InetAddressFactory.newNonLoopback().getHostAddress());
  2. nodeConfiguration3.setMasterUri(getMasterUri());//如果没有设置默认值为 "http://localhost:11311/"
  3. nodeConfiguration3.setNodeName("android_sensors_driver_imu");
 
DefaultNodeMainExecutor.java的监听器
  1. privateclassRegistrationListenerimplementsNodeListener{
  2. privateRegistrationListener(){
  3. }
  4. publicvoid onStart(ConnectedNode connectedNode){
  5. DefaultNodeMainExecutor.this.registerNode(connectedNode);
  6. }
  7. publicvoid onShutdown(Node node){
  8. }
  9. publicvoid onShutdownComplete(Node node){
  10. DefaultNodeMainExecutor.this.unregisterNode(node);
  11. }
  12. publicvoid onError(Node node,Throwable throwable){
  13. DefaultNodeMainExecutor.log.error("Node error.", throwable);
  14. DefaultNodeMainExecutor.this.unregisterNode(node);
  15. }
  16. }
  17. }
 
发布者的监听器
  1. //@Override
  2. publicvoid onStart(ConnectedNode node)
  3. {
  4. try
  5. {
  6. this.publisher = node.newPublisher("android/fix","sensor_msgs/NavSatFix");
  7. this.navSatFixListener =newNavSatListener(publisher);
  8. this.navSatThread =newNavSatThread(this.locationManager,this.navSatFixListener);
  9. this.navSatThread.start();
  10. }
  11. catch(Exception e)
  12. {
  13. if(node !=null)
  14. {
  15. node.getLog().fatal(e);
  16. }
  17. else
  18. {
  19. e.printStackTrace();
  20. }
  21. }
  22. }
  23. //@Override
  24. publicvoid onShutdown(Node arg0){
  25. this.navSatThread.shutdown();
  26. try{
  27. this.navSatThread.join();
  28. }catch(InterruptedException e){
  29. e.printStackTrace();
  30. }
  31. }
  32. //@Override
  33. publicvoid onShutdownComplete(Node arg0){
  34. }
  35. publicvoid onError(Node node,Throwable throwable)
  36. {
  37. }
 
 

ros和Android(一)

标签:

原文地址:http://www.cnblogs.com/baldermurphy/p/5789310.html

(0)
(0)
   
举报
评论 一句话评论(0
登录后才能评论!
© 2014 mamicode.com 版权所有  联系我们:gaon5@hotmail.com
迷上了代码!