Skip to content

Commit

Permalink
Moved configuration messages to autoware_config_msgs
Browse files Browse the repository at this point in the history
  • Loading branch information
esteve committed Oct 23, 2018
1 parent f4ace2c commit 8bf1c47
Show file tree
Hide file tree
Showing 96 changed files with 512 additions and 158 deletions.
Expand Up @@ -5,7 +5,7 @@ FIND_PACKAGE(catkin REQUIRED COMPONENTS
autoware_build_flags
roscpp
std_msgs
autoware_msgs
autoware_config_msgs
fusion
)
FIND_PACKAGE(CUDA)
Expand All @@ -15,7 +15,7 @@ catkin_package(
CATKIN_DEPENDS
roscpp
std_msgs
autoware_msgs
autoware_config_msgs
fusion
)

Expand Down
Expand Up @@ -32,7 +32,7 @@
#include <std_msgs/Header.h>
#include <fusion/fusion_func.h>
#include "autoware_msgs/ImageObjRanged.h"
#include "autoware_msgs/ConfigCarFusion.h"
#include "autoware_config_msgs/ConfigCarFusion.h"

static void publishTopic();
static ros::Publisher fused_objects;
Expand Down Expand Up @@ -88,7 +88,7 @@ static void publishTopic()
fused_objects.publish(fused_objects_msg);
}

static void config_cb(const autoware_msgs::ConfigCarFusion::ConstPtr& param)
static void config_cb(const autoware_config_msgs::ConfigCarFusion::ConstPtr& param)
{
setParams(param->min_low_height,
param->max_low_height,
Expand Down
Expand Up @@ -12,12 +12,12 @@

<build_depend>roscpp</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>autoware_msgs</build_depend>
<build_depend>autoware_config_msgs</build_depend>
<build_depend>fusion</build_depend>

<run_depend>roscpp</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>autoware_msgs</run_depend>
<run_depend>autoware_config_msgs</run_depend>
<run_depend>fusion</run_depend>

</package>
Expand Up @@ -9,6 +9,7 @@ find_package(catkin REQUIRED COMPONENTS
sensor_msgs
std_msgs
autoware_msgs
autoware_config_msgs
)

find_package(CUDA)
Expand All @@ -22,6 +23,7 @@ catkin_package(CATKIN_DEPENDS
sensor_msgs
std_msgs
autoware_msgs
autoware_config_msgs
)

set(CMAKE_CXX_FLAGS "-O3 -g -Wall ${CMAKE_CXX_FLAGS}")
Expand Down
Expand Up @@ -42,7 +42,7 @@ Launch file available parameters:
|Topic|Type|Objective|
------|----|---------
|`/image_raw`|`sensor_msgs/Image`|Source image stream to perform detection.|
|`/config/Yolo3`|`autoware_msgs/ConfigSsd`|Configuration adjustment for threshold.|
|`/config/Yolo3`|`autoware_config_msgs/ConfigSsd`|Configuration adjustment for threshold.|

### Published topics

Expand Down
Expand Up @@ -11,13 +11,15 @@
<build_depend>sensor_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>autoware_msgs</build_depend>
<build_depend>autoware_config_msgs</build_depend>
<build_depend>cv_bridge</build_depend>
<build_depend>image_transport</build_depend>
<build_depend>roscpp</build_depend>

<run_depend>sensor_msgs</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>autoware_msgs</run_depend>
<run_depend>autoware_config_msgs</run_depend>
<run_depend>cv_bridge</run_depend>
<run_depend>image_transport</run_depend>
<run_depend>roscpp</run_depend>
Expand Down
Expand Up @@ -284,7 +284,7 @@ void Yolo3DetectorNode::image_callback(const sensor_msgs::ImageConstPtr& in_imag
free(darknet_image_.data);
}

void Yolo3DetectorNode::config_cb(const autoware_msgs::ConfigSsd::ConstPtr& param)
void Yolo3DetectorNode::config_cb(const autoware_config_msgs::ConfigSsd::ConstPtr& param)
{
score_threshold_ = param->score_threshold;
}
Expand Down
Expand Up @@ -125,7 +125,7 @@ class Yolo3DetectorNode {
void rgbgr_image(image& im);
image convert_ipl_to_image(const sensor_msgs::ImageConstPtr& msg);
void image_callback(const sensor_msgs::ImageConstPtr& in_image_message);
void config_cb(const autoware_msgs::ConfigSsd::ConstPtr& param);
void config_cb(const autoware_config_msgs::ConfigSsd::ConstPtr& param);
std::vector<std::string> read_custom_names_file(const std::string& in_path);
public:
void Run();
Expand Down
Expand Up @@ -9,6 +9,7 @@ FIND_PACKAGE(catkin REQUIRED COMPONENTS
roscpp
sensor_msgs
std_msgs
autoware_config_msgs
autoware_msgs
libdpm_ttic
)
Expand All @@ -21,6 +22,7 @@ catkin_package(
roscpp
sensor_msgs
std_msgs
autoware_config_msgs
autoware_msgs
libdpm_ttic
)
Expand Down
Expand Up @@ -37,7 +37,7 @@
#include <sensor_msgs/image_encodings.h>

#include "autoware_msgs/ImageObj.h"
#include "autoware_msgs/ConfigPedestrianDpm.h"
#include "autoware_config_msgs/ConfigPedestrianDpm.h"

#include <libdpm_ttic/dpm_ttic.hpp>

Expand Down Expand Up @@ -109,7 +109,7 @@ static void image_raw_cb(const sensor_msgs::Image& image_source)
counter++;
}

static void config_cb(const autoware_msgs::ConfigPedestrianDpm::ConstPtr& param)
static void config_cb(const autoware_config_msgs::ConfigPedestrianDpm::ConstPtr& param)
{
ttic_param.threshold = param->score_threshold;
ttic_param.overlap = param->group_threshold;
Expand Down
Expand Up @@ -13,6 +13,7 @@
<build_depend>roscpp</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>autoware_config_msgs</build_depend>
<build_depend>autoware_msgs</build_depend>
<build_depend>libdpm_ttic</build_depend>
<build_depend>libopencv-dev</build_depend>
Expand All @@ -21,6 +22,7 @@
<run_depend>roscpp</run_depend>
<run_depend>sensor_msgs</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>autoware_config_msgs</run_depend>
<run_depend>autoware_msgs</run_depend>
<run_depend>libdpm_ttic</run_depend>
<run_depend>libopencv-dev</run_depend>
Expand Down
Expand Up @@ -32,7 +32,7 @@
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/image_encodings.h>
#include "autoware_msgs/ConfigSsd.h"
#include "autoware_config_msgs/ConfigSsd.h"
#include "autoware_msgs/DetectedObject.h"
#include "autoware_msgs/DetectedObjectArray.h"

Expand Down Expand Up @@ -130,7 +130,7 @@ class RosSsdApp
}


void config_cb(const autoware_msgs::ConfigSsd::ConstPtr& param)
void config_cb(const autoware_config_msgs::ConfigSsd::ConstPtr& param)
{
score_threshold_ = param->score_threshold;
}
Expand Down
Expand Up @@ -37,7 +37,7 @@
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/image_encodings.h>
#include <autoware_msgs/ConfigCarKf.h>
#include <autoware_config_msgs/ConfigCarKf.h>
#include <autoware_msgs/ImageObjRanged.h>

#include <autoware_msgs/ImageObjTracked.h>
Expand Down Expand Up @@ -918,7 +918,7 @@ void detections_callback(autoware_msgs::ImageObjRanged image_objects_msg)
publish_if_possible();
}

static void kf_config_cb(const autoware_msgs::ConfigCarKf::ConstPtr& param)
static void kf_config_cb(const autoware_config_msgs::ConfigCarKf::ConstPtr& param)
{
if (param->initial_lifespan > 0)
INITIAL_LIFESPAN = param->initial_lifespan;
Expand Down
Expand Up @@ -42,6 +42,7 @@ find_package(catkin REQUIRED COMPONENTS
pcl_ros
sensor_msgs
autoware_msgs
autoware_config_msgs
pcl_conversions
velodyne_pointcloud
ndt_tku
Expand All @@ -53,7 +54,7 @@ find_package(catkin REQUIRED COMPONENTS
## catkin specific configuration ##
###################################
catkin_package(
CATKIN_DEPENDS std_msgs velodyne_pointcloud autoware_msgs ndt_tku ndt_cpu ${PCL_OPENMP_PACKAGES}
CATKIN_DEPENDS std_msgs velodyne_pointcloud autoware_msgs autoware_config_msgs ndt_tku ndt_cpu ${PCL_OPENMP_PACKAGES}
DEPENDS PCL
)

Expand Down
Expand Up @@ -66,8 +66,8 @@
#include <pcl/registration/ndt.h>
#endif

#include <autoware_msgs/ConfigApproximateNdtMapping.h>
#include <autoware_msgs/ConfigNdtMappingOutput.h>
#include <autoware_config_msgs/ConfigApproximateNdtMapping.h>
#include <autoware_config_msgs/ConfigNdtMappingOutput.h>

struct pose
{
Expand Down Expand Up @@ -157,7 +157,7 @@ static nav_msgs::Odometry odom;
static std::ofstream ofs;
static std::string filename;

static void param_callback(const autoware_msgs::ConfigApproximateNdtMapping::ConstPtr& input)
static void param_callback(const autoware_config_msgs::ConfigApproximateNdtMapping::ConstPtr& input)
{
ndt_res = input->resolution;
step_size = input->step_size;
Expand All @@ -181,7 +181,7 @@ static void param_callback(const autoware_msgs::ConfigApproximateNdtMapping::Con
std::cout << "max_submap_size: " << max_submap_size << std::endl;
}

static void output_callback(const autoware_msgs::ConfigNdtMappingOutput::ConstPtr& input)
static void output_callback(const autoware_config_msgs::ConfigNdtMappingOutput::ConstPtr& input)
{
double filter_res = input->filter_res;
std::string filename = input->filename;
Expand Down
Expand Up @@ -63,7 +63,7 @@
#include <pcl/registration/icp.h>
#include <pcl/filters/voxel_grid.h>

#include "autoware_msgs/ConfigICP.h"
#include "autoware_config_msgs/ConfigICP.h"

#include "autoware_msgs/ICPStat.h"

Expand Down Expand Up @@ -169,7 +169,7 @@ static std::string _offset = "linear"; // linear, zero, quadratic
static std::ofstream ofs;
static std::string filename;

static void param_callback(const autoware_msgs::ConfigICP::ConstPtr& input)
static void param_callback(const autoware_config_msgs::ConfigICP::ConstPtr& input)
{
if (_use_gnss != input->init_pos_gnss)
{
Expand Down
Expand Up @@ -65,8 +65,8 @@
#include <pcl/filters/voxel_grid.h>
#endif

#include "autoware_msgs/ConfigNdtMapping.h"
#include "autoware_msgs/ConfigNdtMappingOutput.h"
#include "autoware_config_msgs/ConfigNdtMapping.h"
#include "autoware_config_msgs/ConfigNdtMappingOutput.h"

struct pose {
double x;
Expand Down Expand Up @@ -125,7 +125,7 @@ static bool _use_openmp = false;

static double fitness_score;

static void param_callback(const autoware_msgs::ConfigNdtMapping::ConstPtr& input)
static void param_callback(const autoware_config_msgs::ConfigNdtMapping::ConstPtr& input)
{
ndt_res = input->resolution;
step_size = input->step_size;
Expand All @@ -145,7 +145,7 @@ static void param_callback(const autoware_msgs::ConfigNdtMapping::ConstPtr& inpu
std::cout << "min_add_scan_shift: " << min_add_scan_shift << std::endl;
}

static void output_callback(const autoware_msgs::ConfigNdtMappingOutput::ConstPtr& input)
static void output_callback(const autoware_config_msgs::ConfigNdtMappingOutput::ConstPtr& input)
{
double filter_res = input->filter_res;
std::string filename = input->filename;
Expand Down
Expand Up @@ -67,8 +67,8 @@
#include <pcl_omp_registration/ndt.h>
#endif

#include <autoware_msgs/ConfigNdtMapping.h>
#include <autoware_msgs/ConfigNdtMappingOutput.h>
#include <autoware_config_msgs/ConfigNdtMapping.h>
#include <autoware_config_msgs/ConfigNdtMappingOutput.h>

#include <time.h>

Expand Down Expand Up @@ -176,7 +176,7 @@ static nav_msgs::Odometry odom;
static std::ofstream ofs;
static std::string filename;

static void param_callback(const autoware_msgs::ConfigNdtMapping::ConstPtr& input)
static void param_callback(const autoware_config_msgs::ConfigNdtMapping::ConstPtr& input)
{
ndt_res = input->resolution;
step_size = input->step_size;
Expand All @@ -198,7 +198,7 @@ static void param_callback(const autoware_msgs::ConfigNdtMapping::ConstPtr& inpu
std::cout << "min_add_scan_shift: " << min_add_scan_shift << std::endl;
}

static void output_callback(const autoware_msgs::ConfigNdtMappingOutput::ConstPtr& input)
static void output_callback(const autoware_config_msgs::ConfigNdtMappingOutput::ConstPtr& input)
{
double filter_res = input->filter_res;
std::string filename = input->filename;
Expand Down
Expand Up @@ -77,7 +77,7 @@
#include <pcl_ros/point_cloud.h>
#include <pcl_ros/transforms.h>

#include <autoware_msgs/ConfigNdt.h>
#include <autoware_config_msgs/ConfigNdt.h>

#include <autoware_msgs/NDTStat.h>

Expand Down Expand Up @@ -243,7 +243,7 @@ static unsigned int points_map_num = 0;

pthread_mutex_t mutex;

static void param_callback(const autoware_msgs::ConfigNdt::ConstPtr& input)
static void param_callback(const autoware_config_msgs::ConfigNdt::ConstPtr& input)
{
if (_use_gnss != input->init_pos_gnss)
{
Expand Down
Expand Up @@ -15,6 +15,7 @@
<build_depend>pcl_ros</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>autoware_msgs</build_depend>
<build_depend>autoware_config_msgs</build_depend>
<build_depend>pcl_conversions</build_depend>
<build_depend>message_filters</build_depend>
<build_depend>velodyne_pointcloud</build_depend>
Expand All @@ -32,6 +33,7 @@
<run_depend>pcl_ros</run_depend>
<run_depend>sensor_msgs</run_depend>
<run_depend>autoware_msgs</run_depend>
<run_depend>autoware_config_msgs</run_depend>
<run_depend>pcl_conversions</run_depend>
<run_depend>message_filters</run_depend>
<run_depend>velodyne_pointcloud</run_depend>
Expand Down
Expand Up @@ -13,6 +13,7 @@ find_package(catkin REQUIRED COMPONENTS
roscpp
std_msgs
tf
autoware_config_msgs
autoware_msgs
geometry_msgs
vector_map_msgs
Expand All @@ -27,6 +28,7 @@ catkin_package(
CATKIN_DEPENDS roscpp
tf
std_msgs
autoware_config_msgs
autoware_msgs
geometry_msgs
vector_map_msgs
Expand Down
Expand Up @@ -4,7 +4,7 @@
#include <mutex>
#include <unordered_map>

#include <autoware_msgs/ConfigDecisionMaker.h>
#include <autoware_config_msgs/ConfigDecisionMaker.h>
#include <autoware_msgs/CloudClusterArray.h>
#include <autoware_msgs/LaneArray.h>
#include <autoware_msgs/Waypoint.h>
Expand Down Expand Up @@ -231,7 +231,7 @@ class DecisionMakerNode
void callbackFromTwistCmd(const geometry_msgs::TwistStamped &msg);
void callbackFromSimPose(const geometry_msgs::PoseStamped &msg);
void callbackFromStateCmd(const std_msgs::Int32 &msg);
void callbackFromConfig(const autoware_msgs::ConfigDecisionMaker &msg);
void callbackFromConfig(const autoware_config_msgs::ConfigDecisionMaker &msg);
void callbackFromObjectDetector(const autoware_msgs::CloudClusterArray &msg);

void callbackFromVectorMapArea(const vector_map_msgs::AreaArray &msg);
Expand Down

0 comments on commit 8bf1c47

Please sign in to comment.