mirror of
https://github.com/6-robot/waterplus_map_tools.git
synced 2025-09-15 12:59:09 +08:00
load waypoints from HOME
This commit is contained in:
parent
73ba4a83ec
commit
f6db939d3a
@ -9,8 +9,6 @@
|
||||
<node pkg="tf" type="static_transform_publisher" name="base_to_laser_broadcaster" args="0 0 0 0 0 0 /map /base_link 100"/>
|
||||
|
||||
<!-- Map tools -->
|
||||
<node pkg="waterplus_map_tools" type="wp_edit_node" name="wp_edit_node" output="screen">
|
||||
<param name="load" type="string" value="/home/robot/waypoints.xml"/>
|
||||
</node>
|
||||
<node pkg="waterplus_map_tools" type="wp_edit_node" name="wp_edit_node" output="screen" />
|
||||
|
||||
</launch>
|
||||
|
||||
@ -626,14 +626,28 @@ int main(int argc, char** argv)
|
||||
{
|
||||
ros::init(argc, argv, "wp_edit_node");
|
||||
|
||||
ros::NodeHandle n_param("~");
|
||||
std::string strLoadFile;
|
||||
n_param.param<std::string>("load", strLoadFile, "");
|
||||
char const* home = getenv("HOME");
|
||||
strLoadFile = home;
|
||||
strLoadFile += "/waypoints.xml";
|
||||
|
||||
ros::NodeHandle n_param("~");
|
||||
std::string strParamFile;
|
||||
n_param.param<std::string>("load", strParamFile, "");
|
||||
if(strParamFile.length() > 0)
|
||||
{
|
||||
strLoadFile = strParamFile;
|
||||
}
|
||||
|
||||
if(strLoadFile.length() > 0)
|
||||
{
|
||||
ROS_INFO("Load waypoints from file : %s",strLoadFile.c_str());
|
||||
LoadWaypointsFromFile(strLoadFile);
|
||||
}
|
||||
else
|
||||
{
|
||||
ROS_WARN("strLoadFile is empty. Failed to load waypoints!");
|
||||
}
|
||||
|
||||
ros::NodeHandle nh;
|
||||
|
||||
|
||||
@ -391,14 +391,29 @@ int main(int argc, char** argv)
|
||||
{
|
||||
ros::init(argc, argv, "wp_waypoint_manager");
|
||||
|
||||
ros::NodeHandle n_param("~");
|
||||
std::string strLoadFile;
|
||||
n_param.param<std::string>("load", strLoadFile, "");
|
||||
char const* home = getenv("HOME");
|
||||
strLoadFile = home;
|
||||
strLoadFile += "/waypoints.xml";
|
||||
|
||||
ros::NodeHandle n_param("~");
|
||||
std::string strParamFile;
|
||||
n_param.param<std::string>("load", strParamFile, "");
|
||||
if(strParamFile.length() > 0)
|
||||
{
|
||||
strLoadFile = strParamFile;
|
||||
}
|
||||
|
||||
if(strLoadFile.length() > 0)
|
||||
{
|
||||
ROS_INFO("Load waypoints from file : %s",strLoadFile.c_str());
|
||||
LoadWaypointsFromFile(strLoadFile);
|
||||
}
|
||||
else
|
||||
{
|
||||
ROS_WARN("strLoadFile is empty. Failed to load waypoints!");
|
||||
}
|
||||
|
||||
|
||||
ros::NodeHandle nh;
|
||||
marker_pub = nh.advertise<visualization_msgs::Marker>("waypoints_marker", 100);
|
||||
|
||||
@ -45,11 +45,11 @@ int main(int argc, char** argv)
|
||||
ros::ServiceClient cliSave = nh.serviceClient<waterplus_map_tools::SaveWaypoints>("/waterplus/save_waypoints");
|
||||
waterplus_map_tools::SaveWaypoints srvS;
|
||||
|
||||
char basePath[1024];
|
||||
memset(basePath, '\0', sizeof(basePath));
|
||||
getcwd(basePath, 999);
|
||||
std::string base_path(basePath);
|
||||
srvS.request.filename = base_path + "/waypoints.xml";
|
||||
std::string strSaveFile;
|
||||
char const* home = getenv("HOME");
|
||||
strSaveFile = home;
|
||||
strSaveFile += "/waypoints.xml";
|
||||
srvS.request.filename = strSaveFile;
|
||||
|
||||
for(int i=1; i<argc; i++)
|
||||
{
|
||||
|
||||
Loading…
Reference in New Issue
Block a user