Skip to content

Commit

Permalink
Merge pull request #791 from CPFL/feature/release-debians-766
Browse files Browse the repository at this point in the history
Feature/release debians 766
  • Loading branch information
dejanpan committed Sep 13, 2017
2 parents 86d7a8e + 4ffa46d commit 1508122
Show file tree
Hide file tree
Showing 12 changed files with 86 additions and 256 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -23,75 +23,17 @@ else()
endif()

set(CMAKE_CXX_FLAGS "-std=c++11 ${CMAKE_CXX_FLAGS}")
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()

################################################
## Declare ROS messages, services and actions ##
################################################

## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependencies might have been
## pulled in transitively but can be declared for certainty nonetheless:
## * add a build_depend tag for "message_generation"
## * add a run_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)

## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )

## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )

## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )

## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# std_msgs # Or other packages containing msgs
# )

###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if you package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
INCLUDE_DIRS include ${EIGEN3_INCLUDE_DIRS}
INCLUDE_DIRS include
LIBRARIES vectormap
CATKIN_DEPENDS vector_map
DEPENDS Eigen3
)

include_directories(
Expand All @@ -107,5 +49,14 @@ add_library(vectormap STATIC

target_link_libraries(vectormap
${catkin_LIBRARIES}
vector_map
)

install(TARGETS vectormap
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})

install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
PATTERN ".svn" EXCLUDE
)
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@
<license>BSD</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>vector_map</build_depend>
<build_depend>eigen</build_depend>
<run_depend>vector_map</run_depend>
<run_depend>eigen</run_depend>
<export></export>
</package>
Original file line number Diff line number Diff line change
@@ -1,12 +1,9 @@
//#include "ros/ros.h"
//#include "std_msgs/String.h"
#include <stdio.h>
#include <stdlib.h>
#include <math.h>
#include "vector_map.h"
#include "libvectormap/vector_map.h"
#include <vector>
#include <map>
#include <tf/transform_listener.h>

void VectorMap::load_points(const vector_map::PointArray& msg)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
#include <iostream>
#include <ros/ros.h>
#include "Rate.h"
#include "vector_map.h"
#include "libvectormap/vector_map.h"
#include <tf/tf.h>
#include <tf/transform_listener.h>
#include <sensor_msgs/CameraInfo.h>
Expand All @@ -18,7 +18,7 @@
#include <geometry_msgs/PoseStamped.h>
#include <signal.h>
#include <cstdio>
#include "Math.h"
#include "libvectormap/Math.h"
#include <Eigen/Eigen>
#include <autoware_msgs/Signals.h>
#include <autoware_msgs/adjust_xy.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@ find_package(catkin REQUIRED COMPONENTS
tf
geometry_msgs
autoware_msgs
nav_msgs
std_msgs
)


Expand Down Expand Up @@ -42,4 +44,13 @@ include_directories(
add_executable(can_info_translator nodes/can_info_translator/can_info_translator_node.cpp
nodes/can_info_translator/can_info_translator_core.cpp)
target_link_libraries(can_info_translator ${catkin_LIBRARIES})
add_dependencies(can_info_translator autoware_msgs_generate_messages_cpp)
add_dependencies(can_info_translator ${catkin_EXPORTED_TARGETS})

install(TARGETS can_info_translator
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})

install(DIRECTORY launch/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
PATTERN ".svn" EXCLUDE)
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,13 @@
<build_depend>roscpp</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>autoware_msgs</build_depend>
<build_depend>nav_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<run_depend>roscpp</run_depend>
<run_depend>geometry_msgs</run_depend>
<run_depend>autoware_msgs</run_depend>
<run_depend>nav_msgs</run_depend>
<run_depend>std_msgs</run_depend>

<export>
</export>
Expand Down
70 changes: 35 additions & 35 deletions ros/src/data/packages/vector_map/include/vector_map/vector_map.h
Original file line number Diff line number Diff line change
Expand Up @@ -323,41 +323,41 @@ std::vector<T> parse(const std::string& csv_file)
return objs;
}

namespace
{
void updatePoint(std::map<Key<Point>, Point>& map, const PointArray& msg);
void updateVector(std::map<Key<Vector>, Vector>& map, const VectorArray& msg);
void updateLine(std::map<Key<Line>, Line>& map, const LineArray& msg);
void updateArea(std::map<Key<Area>, Area>& map, const AreaArray& msg);
void updatePole(std::map<Key<Pole>, Pole>& map, const PoleArray& msg);
void updateBox(std::map<Key<Box>, Box>& map, const BoxArray& msg);
void updateDTLane(std::map<Key<DTLane>, DTLane>& map, const DTLaneArray& msg);
void updateNode(std::map<Key<Node>, Node>& map, const NodeArray& msg);
void updateLane(std::map<Key<Lane>, Lane>& map, const LaneArray& msg);
void updateWayArea(std::map<Key<WayArea>, WayArea>& map, const WayAreaArray& msg);
void updateRoadEdge(std::map<Key<RoadEdge>, RoadEdge>& map, const RoadEdgeArray& msg);
void updateGutter(std::map<Key<Gutter>, Gutter>& map, const GutterArray& msg);
void updateCurb(std::map<Key<Curb>, Curb>& map, const CurbArray& msg);
void updateWhiteLine(std::map<Key<WhiteLine>, WhiteLine>& map, const WhiteLineArray& msg);
void updateStopLine(std::map<Key<StopLine>, StopLine>& map, const StopLineArray& msg);
void updateZebraZone(std::map<Key<ZebraZone>, ZebraZone>& map, const ZebraZoneArray& msg);
void updateCrossWalk(std::map<Key<CrossWalk>, CrossWalk>& map, const CrossWalkArray& msg);
void updateRoadMark(std::map<Key<RoadMark>, RoadMark>& map, const RoadMarkArray& msg);
void updateRoadPole(std::map<Key<RoadPole>, RoadPole>& map, const RoadPoleArray& msg);
void updateRoadSign(std::map<Key<RoadSign>, RoadSign>& map, const RoadSignArray& msg);
void updateSignal(std::map<Key<Signal>, Signal>& map, const SignalArray& msg);
void updateStreetLight(std::map<Key<StreetLight>, StreetLight>& map, const StreetLightArray& msg);
void updateUtilityPole(std::map<Key<UtilityPole>, UtilityPole>& map, const UtilityPoleArray& msg);
void updateGuardRail(std::map<Key<GuardRail>, GuardRail>& map, const GuardRailArray& msg);
void updateSideWalk(std::map<Key<SideWalk>, SideWalk>& map, const SideWalkArray& msg);
void updateDriveOnPortion(std::map<Key<DriveOnPortion>, DriveOnPortion>& map, const DriveOnPortionArray& msg);
void updateCrossRoad(std::map<Key<CrossRoad>, CrossRoad>& map, const CrossRoadArray& msg);
void updateSideStrip(std::map<Key<SideStrip>, SideStrip>& map, const SideStripArray& msg);
void updateCurveMirror(std::map<Key<CurveMirror>, CurveMirror>& map, const CurveMirrorArray& msg);
void updateWall(std::map<Key<Wall>, Wall>& map, const WallArray& msg);
void updateFence(std::map<Key<Fence>, Fence>& map, const FenceArray& msg);
void updateRailCrossing(std::map<Key<RailCrossing>, RailCrossing>& map, const RailCrossingArray& msg);
} // namespace
/* namespace */
/* { */
/* void updatePoint(std::map<Key<Point>, Point>& map, const PointArray& msg); */
/* void updateVector(std::map<Key<Vector>, Vector>& map, const VectorArray& msg); */
/* void updateLine(std::map<Key<Line>, Line>& map, const LineArray& msg); */
/* void updateArea(std::map<Key<Area>, Area>& map, const AreaArray& msg); */
/* void updatePole(std::map<Key<Pole>, Pole>& map, const PoleArray& msg); */
/* void updateBox(std::map<Key<Box>, Box>& map, const BoxArray& msg); */
/* void updateDTLane(std::map<Key<DTLane>, DTLane>& map, const DTLaneArray& msg); */
/* void updateNode(std::map<Key<Node>, Node>& map, const NodeArray& msg); */
/* void updateLane(std::map<Key<Lane>, Lane>& map, const LaneArray& msg); */
/* void updateWayArea(std::map<Key<WayArea>, WayArea>& map, const WayAreaArray& msg); */
/* void updateRoadEdge(std::map<Key<RoadEdge>, RoadEdge>& map, const RoadEdgeArray& msg); */
/* void updateGutter(std::map<Key<Gutter>, Gutter>& map, const GutterArray& msg); */
/* void updateCurb(std::map<Key<Curb>, Curb>& map, const CurbArray& msg); */
/* void updateWhiteLine(std::map<Key<WhiteLine>, WhiteLine>& map, const WhiteLineArray& msg); */
/* void updateStopLine(std::map<Key<StopLine>, StopLine>& map, const StopLineArray& msg); */
/* void updateZebraZone(std::map<Key<ZebraZone>, ZebraZone>& map, const ZebraZoneArray& msg); */
/* void updateCrossWalk(std::map<Key<CrossWalk>, CrossWalk>& map, const CrossWalkArray& msg); */
/* void updateRoadMark(std::map<Key<RoadMark>, RoadMark>& map, const RoadMarkArray& msg); */
/* void updateRoadPole(std::map<Key<RoadPole>, RoadPole>& map, const RoadPoleArray& msg); */
/* void updateRoadSign(std::map<Key<RoadSign>, RoadSign>& map, const RoadSignArray& msg); */
/* void updateSignal(std::map<Key<Signal>, Signal>& map, const SignalArray& msg); */
/* void updateStreetLight(std::map<Key<StreetLight>, StreetLight>& map, const StreetLightArray& msg); */
/* void updateUtilityPole(std::map<Key<UtilityPole>, UtilityPole>& map, const UtilityPoleArray& msg); */
/* void updateGuardRail(std::map<Key<GuardRail>, GuardRail>& map, const GuardRailArray& msg); */
/* void updateSideWalk(std::map<Key<SideWalk>, SideWalk>& map, const SideWalkArray& msg); */
/* void updateDriveOnPortion(std::map<Key<DriveOnPortion>, DriveOnPortion>& map, const DriveOnPortionArray& msg); */
/* void updateCrossRoad(std::map<Key<CrossRoad>, CrossRoad>& map, const CrossRoadArray& msg); */
/* void updateSideStrip(std::map<Key<SideStrip>, SideStrip>& map, const SideStripArray& msg); */
/* void updateCurveMirror(std::map<Key<CurveMirror>, CurveMirror>& map, const CurveMirrorArray& msg); */
/* void updateWall(std::map<Key<Wall>, Wall>& map, const WallArray& msg); */
/* void updateFence(std::map<Key<Fence>, Fence>& map, const FenceArray& msg); */
/* void updateRailCrossing(std::map<Key<RailCrossing>, RailCrossing>& map, const RailCrossingArray& msg); */
/* } // namespace */

class VectorMap
{
Expand Down
10 changes: 6 additions & 4 deletions ros/src/data/packages/vector_map_server/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,6 @@ find_package(catkin REQUIRED COMPONENTS
autoware_msgs
vector_map_msgs
vector_map
jsk_recognition_msgs
jsk_rviz_plugins
message_generation
)

Expand Down Expand Up @@ -51,8 +49,6 @@ generate_messages(
geometry_msgs
autoware_msgs
vector_map_msgs
jsk_recognition_msgs
jsk_rviz_plugins
)

catkin_package(
Expand All @@ -76,3 +72,9 @@ add_dependencies(vector_map_client
vector_map_server_generate_messages_cpp
${catkin_EXPORTED_TARGETS}
)


install(TARGETS vector_map_server vector_map_client
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
Loading

0 comments on commit 1508122

Please sign in to comment.