Skip to content

Commit

Permalink
Merge pull request #1 from autowarefoundation/master
Browse files Browse the repository at this point in the history
Merge left over features from around the 1.11 release (autowarefoundation#2151)
  • Loading branch information
hatem-darweesh authored Mar 27, 2019
2 parents 276073b + 6a7d1b9 commit 4ce35ca
Show file tree
Hide file tree
Showing 19 changed files with 169 additions and 30 deletions.
2 changes: 1 addition & 1 deletion docs/quick_start/my_mission_planning.launch
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

<!-- waypoint_loader -->
<node pkg="rostopic" type="rostopic" name="config_waypoint_loader_rostopic"
args="pub -l /config/waypoint_loader autoware_msgs/ConfigWaypointLoader
args="pub -l /config/waypoint_loader autoware_config_msgs/ConfigWaypointLoader
'{multi_lane_csv: '$(env HOME)/.autoware/data/path/moriyama_path.txt', replanning_mode: false, velocity_max: 20.0, velocity_min: 4.0, accel_limit: 0.98, decel_limit: 0.98, radius_thresh: 20.0, radius_min: 6.0, resample_mode: true, resample_interval: 1.0, velocity_offset: 4, end_point_offset: 5}' "
/>
<include file="$(find waypoint_maker)/launch/waypoint_loader.launch" />
Expand Down
28 changes: 16 additions & 12 deletions ros/run
Original file line number Diff line number Diff line change
Expand Up @@ -6,20 +6,10 @@ MY_PATH=$(readlink -f $(dirname $0))
OPTION_WORKING_DIR='--working-directory'
OPTION_CORE_GEOMETRY='--geometry=50x10+0+0'
OPTION_RM_GEOMETRY='--geometry=50x10+500+0'
OPTION_TITLE='--title'
OPTION_COMMAND='--command'


MASTER_DISPLAY_OPTION="${OPTION_CORE_GEOMETRY} ${OPTION_TITLE}\=\"roscore\""
RUNMGR_DISPLAY_OPTION="${OPTION_RM_GEOMETRY} ${OPTION_TITLE}\=\"runtime_manager\""

if [ $(which gnome-terminal) ]; then
TERMINAL=gnome-terminal
GNOME_VERSION=$(gnome-terminal --version | cut -d '.' -f 2)
if [ ${GNOME_VERSION} -ge 14 ]; then
MASTER_DISPLAY_OPTION=''
RUNMGR_DISPLAY_OPTION=''
fi
elif [ $(which mate-terminal) ]; then
if [ $(which mate-terminal) ]; then
TERMINAL=mate-terminal
elif [ $(which xfce4-terminal) ]; then
TERMINAL=xfce4-terminal
Expand All @@ -35,6 +25,20 @@ elif [ $(which konsole) ]; then
OPTION_TITLE='-T'
fi

MASTER_DISPLAY_OPTION="${OPTION_CORE_GEOMETRY} ${OPTION_TITLE}=\"roscore\""
RUNMGR_DISPLAY_OPTION="${OPTION_RM_GEOMETRY} ${OPTION_TITLE}=\"runtime_manager\""

if [ $(which gnome-terminal) ]; then
TERMINAL=gnome-terminal
GNOME_VERSION=$(gnome-terminal --version | cut -d '.' -f 2)
if [ ${GNOME_VERSION} -ge 14 ]; then
MASTER_DISPLAY_OPTION=''
RUNMGR_DISPLAY_OPTION=''
fi
fi

echo "Process Manager"

sudo bash -c "$MY_PATH/run_proc_manager &"

ADDR=$($MY_PATH/src/.config/rviz/subnet_chk.py -)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ template<typename _Tp> class RectClassScore
case Yolo3::KEYBOARD: return "keyboard";
case Yolo3::CELL_PHONE: return "cellphone";
case Yolo3::MICROWAVE: return "microwave";
case Yolo3::OVEN: return "over";
case Yolo3::OVEN: return "oven";
case Yolo3::TOASTER: return "toaster";
case Yolo3::SINK: return "sink";
case Yolo3::REFRIGERATOR: return "refrigerator";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -381,7 +381,7 @@ void DecisionMaker::InitBehaviorStates()

double deceleration_critical = 0;
double inv_time = 2.0*((beh.followDistance- (critical_long_front_distance+m_params.additionalBrakingDistance))-CurrStatus.speed);
if(inv_time == 0)
if(inv_time <= 0)
deceleration_critical = m_CarInfo.max_deceleration;
else
deceleration_critical = CurrStatus.speed*CurrStatus.speed/inv_time;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,5 +14,5 @@
publish: [/points_clipped]
subscribe: [/points_raw]
- name: /compare_map_filter
publish: [/match_points, /unmatch_points]
subscribe: [/points_raw, /points_map]
publish: [/points_ground, /points_no_ground]
subscribe: [/config/compare_map_filter, /points_raw, /points_map]
Original file line number Diff line number Diff line change
@@ -1,18 +1,18 @@
<launch>
<arg name="input_point_topic" default="/points_raw" />
<arg name="input_map_topic" default="/points_map" />
<arg name="output_match_topic" default="/match_points" />
<arg name="output_unmatch_topic" default="/unmatch_points" />
<arg name="output_match_topic" default="/points_ground" />
<arg name="output_unmatch_topic" default="/points_no_ground" />

<arg name="distance_threshold" default="0.2" />
<arg name="distance_threshold" default="0.3" />
<arg name="min_clipping_height" default="-2.0" />
<arg name="max_clipping_height" default="0.5" />

<node pkg="points_preprocessor" type="compare_map_filter" name="compare_map_filter">
<remap from="/points_raw" to="$(arg input_point_topic)"/>
<remap from="/points_map" to="$(arg input_map_topic)"/>
<remap from="/match_points" to="$(arg output_match_topic)"/>
<remap from="/unmatch_points" to="$(arg output_unmatch_topic)"/>
<remap from="/points_ground" to="$(arg output_match_topic)"/>
<remap from="/points_no_ground" to="$(arg output_unmatch_topic)"/>

<param name="distance_threshold" value="$(arg distance_threshold)" />
<param name="min_clipping_height" value="$(arg min_clipping_height)" />
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ Launch file available parameters:
|`input_map_topic`|*String*|PointCloud Map topic. Default `/points_map`.|
|`output_match_topic`|*String*|Comparing LiDAR PointCloud and PointCloud Map, topic of the PointCloud which matched. Default `/match_points`.|
|`output_unmatch_topic`|*String*|Comparing LiDAR PointCloud and PointCloud Map, topic of the PointCloud which unmatched. Default `/unmatch_points`.|
|`distance_threshold`|*Double*|Threshold for comparing LiDAR PointCloud and PointCloud Map. Euclidean distance (mether). Default `0.2`.|
|`distance_threshold`|*Double*|Threshold for comparing LiDAR PointCloud and PointCloud Map. Euclidean distance (mether). Default `0.3`.|
|`min_clipping_height`|*Double*|Remove the points where the height is lower than the threshold. (Based on sensor coordinates). Default `-2.0`.|
|`max_clipping_height`|*Double*|Remove the points where the height is higher than the threshold. (Based on sensor coordinates). Default `0.5`.|

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ CompareMapFilter::CompareMapFilter()
: nh_()
, nh_private_("~")
, tf_listener_(new tf::TransformListener)
, distance_threshold_(0.2)
, distance_threshold_(0.3)
, min_clipping_height_(-2.0)
, max_clipping_height_(0.5)
, map_frame_("/map")
Expand Down Expand Up @@ -196,10 +196,12 @@ void CompareMapFilter::searchMatchingCloud(const pcl::PointCloud<pcl::PointXYZI>

std::vector<int> nn_indices(1);
std::vector<float> nn_dists(1);
const double squared_distance_threshold = distance_threshold_ * distance_threshold_;

for (size_t i = 0; i < in_cloud_ptr->points.size(); ++i)
{
tree_.nearestKSearch(in_cloud_ptr->points[i], 1, nn_indices, nn_dists);
if (nn_dists[0] <= distance_threshold_)
if (nn_dists[0] <= squared_distance_threshold)
{
match_cloud_ptr->points.push_back(in_cloud_ptr->points[i]);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,3 +70,7 @@ catkin_install_python(PROGRAMS
install(DIRECTORY launch/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
PATTERN ".svn" EXCLUDE)

install(DIRECTORY docs/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/docs
PATTERN ".svn" EXCLUDE)
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,7 @@ void Autoware_Rosbag_Plugin::on_button_record_start_clicked()

/* Caculate max split size */
if (split_size != 0 && ui->checkBox_split_size->isChecked())
recoParam.max_size = ceil(split_size * 1048576 * 1024);
recoParam.max_size = ceil(split_size * 1000 * 1000 * 1000);
else
recoParam.max_size = 0;

Expand Down Expand Up @@ -243,7 +243,7 @@ int Autoware_Rosbag_Plugin::recordReq( RecordParam &recoParam )
ROS_INFO("%s L.%d - chunk_size [%d]", __FUNCTION__, __LINE__, recorder_opts_->chunk_size);
ROS_INFO("%s L.%d - limit [%d]", __FUNCTION__, __LINE__, recorder_opts_->limit);
ROS_INFO("%s L.%d - split [%d]", __FUNCTION__, __LINE__, recorder_opts_->split);
ROS_INFO("%s L.%d - max_size [%.2fGB]", __FUNCTION__, __LINE__, recorder_opts_->max_size / 1048576.0 / 1024.0);
ROS_INFO("%s L.%d - max_size [%.2fGB]", __FUNCTION__, __LINE__, recorder_opts_->max_size / 1000.0 / 1000.0 / 1000.0);
ROS_INFO("%s L.%d - max_duration [%.1fmin]", __FUNCTION__, __LINE__, recorder_opts_->max_duration.toSec() / 60.0 );
ROS_INFO("%s L.%d - node [%s]", __FUNCTION__, __LINE__, recorder_opts_->node.c_str() );
ROS_INFO("%s L.%d - min_space [%d]", __FUNCTION__, __LINE__, recorder_opts_->min_space );
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ class Autoware_Rosbag_Plugin : public rviz::Panel
std::string filename;
std::vector<std::string> topics;
int max_duration;
uint32_t max_size;
uint64_t max_size;
} RecordParam;

protected:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ struct ROSBAG_DECL RecorderOptions
uint32_t chunk_size;
uint32_t limit;
bool split;
uint32_t max_size;
uint64_t max_size;
uint32_t max_splits;
ros::Duration max_duration;
std::string node;
Expand Down
2 changes: 1 addition & 1 deletion ros/src/util/packages/runtime_manager/scripts/sensing.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -1411,7 +1411,7 @@ params :
label : distance_threshold
min : 0.01
max : 100
v : 0.2
v : 0.3
cmd_param :
dash : ''
delim : ':='
Expand Down
19 changes: 19 additions & 0 deletions ros/src/vehicle/vehicle_description/launch/lexus.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<!-- -->
<launch>
<arg name="base_frame" default="/base_link"/>
<arg name="topic_name" default="vehicle_model"/>
<arg name="offset_x" default="1.2"/>
<arg name="offset_y" default="0.0"/>
<arg name="offset_z" default="0.0"/>
<arg name="offset_roll" default="0.0"/> <!-- degree -->
<arg name="offset_pitch" default="0.0"/> <!-- degree -->
<arg name="offset_yaw" default="0.0"/> <!-- degree -->
<arg name="model_path" default="$(find vehicle_description)/urdf/lexus.urdf" />
<arg name="gui" default="False" />

<param name="robot_description" textfile="$(arg model_path)" />
<param name="use_gui" value="$(arg gui)"/>
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />

</launch>
Binary file modified ros/src/vehicle/vehicle_description/mesh/estima_left_white.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file modified ros/src/vehicle/vehicle_description/mesh/estima_right_white.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
99 changes: 99 additions & 0 deletions ros/src/vehicle/vehicle_description/mesh/lexus.dae

Large diffs are not rendered by default.

Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
11 changes: 11 additions & 0 deletions ros/src/vehicle/vehicle_description/urdf/lexus.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
<?xml version="1.0"?>
<robot name="car">
<link name="base_link">
<visual name="base_visual">
<origin xyz="1 0 0.0" rpy="1.57 0 3.14" />
<geometry>
<mesh filename="package://vehicle_description/mesh/lexus.dae" scale="1.0 1.0 1.0"/>
</geometry>
</visual>
</link>
</robot>

0 comments on commit 4ce35ca

Please sign in to comment.