|
@@ -11,6 +11,9 @@
|
|
|
#include <stdint.h>
|
|
|
#include <string>
|
|
|
|
|
|
+#include <QUdpSocket>
|
|
|
+#include <QNetworkDatagram>
|
|
|
+
|
|
|
#include <nav_msgs/Odometry.h>
|
|
|
#include <geometry_msgs/PointStamped.h>
|
|
|
#include <geometry_msgs/TwistStamped.h>
|
|
@@ -137,10 +140,11 @@ void callback_imu(const sensor_msgs::ImuConstPtr& msg)
|
|
|
int main(int argc, char **argv)
|
|
|
{
|
|
|
//Initiate ROS
|
|
|
- ros::init(argc, argv, "pilottoros");
|
|
|
+ ros::init(argc, argv, "rtk_nav992");
|
|
|
ros::NodeHandle private_nh("~");
|
|
|
- ros::Rate loop_rate(100);
|
|
|
+ ros::Rate loop_rate(100);
|
|
|
|
|
|
+ QUdpSocket *mudpSocketGPSIMU;
|
|
|
|
|
|
private_nh.getParam("pose_topic",_pose_topic);
|
|
|
private_nh.getParam("twist_topic",_twist_topic);
|
|
@@ -165,7 +169,7 @@ int main(int argc, char **argv)
|
|
|
|
|
|
while (ros::ok())
|
|
|
{
|
|
|
-
|
|
|
+ ros::spinOnce();
|
|
|
double x_o, y_o;
|
|
|
double x_now, y_now;
|
|
|
GaussProjCal(glon0, glat0, &x_o, &y_o);
|
|
@@ -215,9 +219,20 @@ int main(int argc, char **argv)
|
|
|
}
|
|
|
|
|
|
|
|
|
- ros::spin();
|
|
|
+ //ros::spin();
|
|
|
loop_rate.sleep();
|
|
|
}
|
|
|
|
|
|
return 0;
|
|
|
}
|
|
|
+
|
|
|
+#if 0
|
|
|
+rostopic pub -r 10 /nav992_devicewist geometry_msgs/Twist "linear:
|
|
|
+ x: 0.0
|
|
|
+ y: 0.0
|
|
|
+ z: 0.0
|
|
|
+angular:
|
|
|
+ x: 0.0
|
|
|
+ y: 0.0
|
|
|
+ z: 1.0"
|
|
|
+#endif
|