Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
19 changes: 12 additions & 7 deletions rtklib_bridge/launch/rtklib_bridge.launch
Original file line number Diff line number Diff line change
@@ -1,11 +1,16 @@
<?xml version="1.0" encoding="UTF-8"?>

<launch>

<param name="ip_adress" value="127.0.0.1"/>
<param name="port" value="61111"/>
<param name="altitude_estimate" value="false"/>
<arg name="pub_vel_topic_name" default="/rtklib_nav_doppler"/>
<arg name="address" default="127.0.0.1"/>
<arg name="port_num" default="61112"/>
<arg name="est_alt" default="false"/>

<!-- When outputting on ellipsoidal height (WGS 84) = false ,When outputting in altitude = true -->
<node pkg="rtklib_bridge" name="rtklib_bridge" type="rtklib_bridge" respawn="true"/>

<node pkg="rtklib_bridge" name="rtklib_bridge" type="rtklib_bridge" respawn="true">
<param name="pub_vel_topic" value="$(arg pub_vel_topic_name)"/>
<param name="ip_adress" value="$(arg address)"/>
<param name="port" value="$(arg port_num)"/>
<param name="altitude_estimate" value="$(arg est_alt)"/>
</node>
</launch>

12 changes: 8 additions & 4 deletions rtklib_bridge/src/rtklib_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,11 @@ int main(int argc, char** argv)
{
ros::init(argc, argv, "rtklib_bridge");
ros::NodeHandle n;
ros::Publisher pub1 = n.advertise<rtklib_msgs::RtklibNav>("rtklib_nav", 1);

std::string pub_vel_topic_;
n.param("/rtklib_bridge/pub_vel_topic", pub_vel_topic_, std::string("rtklib_nav_doppler"));

ros::Publisher pub1 = n.advertise<rtklib_msgs::RtklibNav>(pub_vel_topic_, 1);
ros::Publisher pub2 = n.advertise<sensor_msgs::NavSatFix>("rtklib/fix", 1000);

rtklib_msgs::RtklibNav rtklib_nav;
Expand All @@ -56,9 +60,9 @@ int main(int argc, char** argv)
std::string ip_adress = "127.0.0.1";
int port = 61111;
bool altitude_estimate = true;
n.getParam("ip_adress", ip_adress);
n.getParam("port", port);
n.getParam("altitude_estimate", altitude_estimate);
n.getParam("/rtklib_bridge/ip_adress", ip_adress);
n.getParam("/rtklib_bridge/port", port);
n.getParam("/rtklib_bridge/altitude_estimate", altitude_estimate);

std::cout << "ip_adress " << ip_adress << std::endl;
std::cout << "port "<< port <<std::endl;
Expand Down