Giter VIP home page Giter VIP logo

selfie_carolocup2019's Introduction

Selfie @ Carolo-Cup 2019

This repository contains the catkin workspace for Selfie Autonomous Car at Carolo-Cup 2019 competition.

Build instructions

The project is targetting ROS Kinetic Kame distribution. Before proceeding, make sure you have it installed on your development machine.

First, clone the repository to a convenient location using:

git clone --recurse-submodules https://github.com/KNR-Selfie/selfie_carolocup2019

Navigate to the main directory with:

cd selfie_carolocup2019

Lastly, the following set of commands will in turn download all external dependencies, build the packages in src directory and include them in your environment.

./resolve-dependencies.sh
catkin_make
source ./devel/setup.bash

Running

roslaunch selfie initialization.launch

Remember to put an appropriate homography_export.yaml file generated from this program in your ROS_HOME directory.

selfie_carolocup2019's People

Contributors

goldob avatar matszczygielski avatar nels3 avatar matmarczuk avatar raflit avatar mkrasa avatar

Stargazers

Einwand avatar  avatar

Watchers

James Cloos avatar  avatar

Forkers

ericflpa knr-pw

selfie_carolocup2019's Issues

Detect cuboid obstacles in LIDAR scans

Implement node detect_obstacles in package selfie_perception, which will be able to detect positions and dimensions of cuboid obstacles in LIDAR scans.

detect_obstacles

Subscribed topics

scan (sensor_msgs/LaserScan)
Laser scan.

Published topics

obstacles (selfie_msgs/PolygonArray)
List of detected obstacles, represented as rectangles in local coordinate space of the vehicle.

Subscribed transformations

base_linklaser

Implement lane change maneuver

Implement node change_lane in package selfie_control, which will be responsible for publishing the setpoint for PID controller (#30) depending on which lane the vehicle is supposed to drive at given moment. The setpoint itself is a linear offset (in meters) from the center line. For now a fixed lane width is assumed. By default the vehicle should drive on the right lane.

The node should implement a ChangeLane ActionServer named change_lane. The action handling flow should look like follows:

  1. New goal is received
  2. If target lane is the same as the one we're currently on, the goal is rejected and we do not proceed further.
  3. Otherwise, the goal is accepted, setpoint is changed accordingly and the correct turn indicator is turned on. We keep track of the vehicle's position on the road.
  4. Once the vehicle reaches the center of the target lane (within marigin of error), the goal is marked as succeeded and the turn indicator is turned off.

Refer to actionlib package documentation to learn more about actions, especially the section on goal state transitions.

change_lane

Parameters

~lane_width (float)
Assumed lane width (in meters).

~error_margin (float)
Maximum distance from center of the target lane (in meters) until the lane change maneuver is considered complete.

Subscribed topics

position_offset (std_msgs/Float64)
Current distance from the center line (in meters). Positive offset is to the left.

Published topics

target_offset (std_msgs/Float64)
Desirable distance from the center line (in meters), used as setpoint for PID controller. Positive offset is to the left. The value should be set depending on which lane the vehicle is supposed to drive on at given moment.

left_turn_indicator (std_msgs/Bool)
right_turn_indicator (std_msgs/Bool)
Flags used to turn on left and right turn indicator, respectively. Should be set to true for the whole period during which the indicator should be turned on - blinking will be handled in a separate program.

Pass control to free drive subsystem after start

Create node pass_control in package selfie_control which in conjunction with a multiplexer instance will be responsible for passing control to free drive subsystem (#1, #29, #4) after successful execution of the starting procedure (#11).

Along with the node should come a launch file with system configuration, including topic remapping etc.

pass_control

Subscribed topics

attempt_started (std_msgs/Bool)
Published as true at the end of the starting procedure.

Services called

mux/select (topic_tools/MuxSelect)
Used to select subsystem which will be taking control of the vehicle.

Estimate position on the road from lane markings

Implement node estimate_position in package selfie_path_planner, which given a set of road markings detections will be able to estimate the vehicle's position with respect to the right lane of the road. This node should assume perfect detection independent of special conditions, such as dashed lines, missing markings etc.

estimate_position

Subscribed topics

road_markings (selfie_msgs/RoadMarkings)
Position of road markings, given as lists of points in local coordinate system of the vehicle.

Published topics

position_offset (std_msgs/Float64)
Distance from the center of the right lane (in meters). Positive offset is to the left.

heading_offset (std_msgs/Float64)
Angle between the vehicle's direction and the tangent to the road (in radians), normalized between -π and π. Positive offset is to the left.

Implement starting procedure

Implement node starting_procedure in package selfie_starting_procedure which will be responsible for controlling the vehicle during starting procedure for both dynamic events, according to Basic-Cup Regulations. The node will be started while still in the starting box (section 6.3.3), so it should detect when the gate is opened and then drive to the track. Once it gets there, it should publish a message signaling start of the attempt and then terminate.

If there is more than one node needed for the task, a launch file can be created instead.

starting_procedure

Parameters

~config_file (string)
Path to the configuration file containing homography matrices.

Subscribed topics

image (sensor_msgs/Image)
Camera image.

scan (sensor_msgs/LaserScan)
Laser scan.

odom (nav_msgs/Odometry)
Odometry data.

Published topics

drive (ackermann_msgs/AckermannDriveStamped)
Steering commands for the vehicle.

attempt_started (std_msgs/Bool)
This topic should be published exactly once as true once the vehicle reaches the track.

Subscribed transformations

base_linklaser

Improve robustness of markings detection algorithm

Improve on detect_markings node in selfie_perception package so that all conceivable scenarios in the Free Drive (w/o Obstacles) and Parking dynamic event from Basic-Cup are handled properly.

These include:

  • missing markings
  • passing the starting lane
  • other part of the track in the field of view
  • artifacts outside the road area, including markings and obstacles
  • driving through the parking area
  • rural intersections (both with and without right of way)

For more details about road specification refer to Basic-Cup Regulations.


This issue replaces #8, #9, #10.

IDS Camera Handler

Create custom node that will take Image from IDS Camera and pass it to ROS.
Reason: ROS packages did not work with our IDS Camera type

Detect road markings from camera images

Implement node detect_markings in package selfie_perception, which given a stream of rectified images along with the homography matrix from the image plane to the road plane will be able to detect positions of road markings with respect to the vehicle. For now, we assume all markings are white and none are missing. For more details about road layout refer to Carolo Basic-Cup Regulations, especially points 5.2.1.2 and 5.2.1.3.

The node should follow the specification given below. In addition, the use of markers to visualize position of both lane lines is highly encouraged.

detect_markings

Parameters

~config_file (string)
Path to the configuration file containing homography matrices.

~point_density (float)
Desired distance between subsequent line points, in meters.

~range (float)
How far ahead to look for road markings, in meters.

Subscribed topics

image_rect (sensor_msgs/Image)
Rectified image.

Published topics

road_markings (selfie_msgs/RoadMarkings)
Markings detected from video, given as lists of points in local coordinate system of the vehicle.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.