Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add waypoint_clicker #26

Merged
merged 1 commit into from
Sep 10, 2015
Merged
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
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,10 @@ target_link_libraries(waypoint_saver gnss ${catkin_LIBRARIES})
add_dependencies(waypoint_saver
waypoint_follower_generate_messages_cpp
vehicle_socket_generate_messages_cpp)

add_executable(waypoint_clicker nodes/waypoint_clicker/waypoint_clicker.cpp)
target_link_libraries(waypoint_clicker ${catkin_LIBRARIES})

add_executable(waypoint_marker_publisher nodes/waypoint_marker_publisher/waypoint_marker_publisher.cpp)
target_link_libraries(waypoint_marker_publisher libwaypoint_follower ${catkin_LIBRARIES})
add_dependencies(waypoint_marker_publisher
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
/*
* Copyright (c) 2015, Nagoya University
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright notice, this
* list of conditions and the following disclaimer.
*
* * Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
*
* * Neither the name of Autoware nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/

#include <fstream>

#include <ros/ros.h>
#include <ros/console.h>
#include <tf/tf.h>
#include <tf/transform_listener.h>
#include <geometry_msgs/PoseWithCovarianceStamped.h>

static tf::StampedTransform transform;
static bool output_first;

static int sub_point_queue_size;

static double velocity; // km/h
static std::string output_file;

static void write_clicked_point(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg)
{
if (output_first) {
std::ofstream ofs(output_file.c_str());
ofs << std::fixed << msg->pose.pose.position.x + transform.getOrigin().x() << ","
<< std::fixed << msg->pose.pose.position.y + transform.getOrigin().y() << ","
<< std::fixed << msg->pose.pose.position.z + transform.getOrigin().z() << std::endl;
} else {
std::ofstream ofs(output_file.c_str(), std::ios_base::app);
ofs << std::fixed << msg->pose.pose.position.x + transform.getOrigin().x() << ","
<< std::fixed << msg->pose.pose.position.y + transform.getOrigin().y() << ","
<< std::fixed << msg->pose.pose.position.z + transform.getOrigin().z() << ","
<< std::fixed << velocity << std::endl;
}

if (output_first)
output_first = false;
}

int main(int argc, char **argv)
{
ros::init(argc, argv, "waypoint_clicker");

ros::NodeHandle n;
n.param<int>("/waypoint_clicker/sub_point_queue_size", sub_point_queue_size, 1);
n.param<double>("/waypoint_clicker/velocity", velocity, 40);
n.param<std::string>("/waypoint_clicker/output_file", output_file, "/tmp/lane_waypoint.csv");

ros::Subscriber sub_point = n.subscribe("/clicked_point", sub_point_queue_size, write_clicked_point);

tf::TransformListener listener;
try {
ros::Time zero = ros::Time(0);
listener.waitForTransform("map", "world", zero, ros::Duration(10));
listener.lookupTransform("map", "world", zero, transform);
} catch (tf::TransformException &ex) {
ROS_ERROR("%s", ex.what());
}
output_first = true;

ros::spin();

return 0;
}
18 changes: 18 additions & 0 deletions ros/src/util/packages/runtime_manager/scripts/computing.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -220,6 +220,9 @@ subs :
gui :
save_filename :
prop : 1
- name : waypoint_clicker
cmd : rosrun waypoint_maker waypoint_clicker
param: waypoint_clicker
- name : waypoint_follower
subs :
- name : pure_pursuit
Expand Down Expand Up @@ -854,6 +857,21 @@ params :
dash : ''
delim : ':='

- name : waypoint_clicker
vars :
- name : velocity
label : Velocity (km/h)
min : 0
max : 200
v : 40.0
rosparam : /waypoint_clicker/velocity
- name : output_file
label : Output File
kind : path
path_type : save
v : /tmp/lane_waypoint.csv
rosparam : /waypoint_clicker/output_file

- name : waypoint_loader
vars :
- name : lane_waypoint
Expand Down