Skip to content

Commit

Permalink
Kinetic Release 1.2.0 (#26)
Browse files Browse the repository at this point in the history
* set ROS hostname to localhost (#15)

Thanks @P4nos 
This makes sense for single machine configuration for local network setup. The roscore should initialise correctly with this fix.

* Added offset in VI Control Loop

Changes made
Added offset in VI control loop to fix bug18
Updated some comments in VI
Fixed gps_imu param name

* Feature/17 redesign full stack with best practices guidelines (#21)

* Code Redesigned

* Bring branch up-to-date

* Fix VI conflict

* Update submodule to latest commit

Co-authored-by: EfimiaPanagiotaki-StreetDrone <efimia@streetdrone.com>
Co-authored-by: P4nos <P4nos@users.noreply.github.com>
Co-authored-by: Fionan-StreetDrone <fionan@streetdrone.com>
Co-authored-by: AbdelrahmanBarghouth-StreetDrone <58561901+AbdelrahmanBarghouth-StreetDrone@users.noreply.github.com>
Co-authored-by: EfimiaPanagiotaki-StreetDrone <efimia@streetdrone.com>
  • Loading branch information
5 people authored Oct 27, 2020
1 parent 2f87cd3 commit cdc43bd
Show file tree
Hide file tree
Showing 23 changed files with 544 additions and 278 deletions.
2 changes: 2 additions & 0 deletions aslan_docker/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,8 @@ RUN useradd -m $USERNAME && \
RUN echo "source /opt/ros/kinetic/setup.bash" >> /home/$USERNAME/.bashrc && \
#Fix for qt and X server errors
echo "export QT_X11_NO_MITSHM=1" >> /home/$USERNAME/.bashrc && \
#Set ROS hostname to localhost
echo "export ROS_HOSTNAME=localhost" >> /home/$USERNAME/.bashrc && \
# cd to home on login
echo "cd" >> /home/$USERNAME/.bashrc

Expand Down
2 changes: 1 addition & 1 deletion src/autoware.ai
Submodule autoware.ai updated 110 files
2 changes: 1 addition & 1 deletion src/msgs/aslan_msgs/msg/SDControl.msg
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
Header header

# Range -100 to 100, -100 is max brake, +100 is max throttle
# Range -100 to 100, -100 is max brake, +100 is max torque
float64 torque

# Range -100 to +100, +100 is maximum left turn
Expand Down
6 changes: 3 additions & 3 deletions src/supervisor/check_message_alive/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,10 @@ include_directories(
${catkin_INCLUDE_DIRS}
)

add_executable(check_message_alive src/check_message_alive.cpp)
add_executable(check_message_alive src/check_message_alive_main.cpp src/check_message_alive.cpp)
target_link_libraries(check_message_alive ${catkin_LIBRARIES})
add_dependencies(check_message_alive ${catkin_EXPORTED_TARGETS})

add_executable(error_listener src/error_listener.cpp)
add_executable(error_listener src/error_listener_main.cpp src/error_listener.cpp)
target_link_libraries(error_listener ${catkin_LIBRARIES})
add_dependencies(error_listener ${catkin_EXPORTED_TARGETS})
add_dependencies(error_listener ${catkin_EXPORTED_TARGETS})
66 changes: 41 additions & 25 deletions src/supervisor/check_message_alive/include/check_message_alive.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,18 @@
#include <string.h>
#include <time.h>

#include <ros/ros.h>
#include <std_msgs/Bool.h>
#include <std_msgs/Int32.h>
#include <sensor_msgs/PointCloud2.h>
#include <geometry_msgs/TwistStamped.h>
#include <geometry_msgs/PoseStamped.h>
#include <aslan_msgs/Lane.h>
#include <aslan_msgs/LaneArray.h>
#include <pcl_conversions/pcl_conversions.h>
#include <tf2_msgs/TFMessage.h>
#include <chrono>

class topic_data
{
public:
Expand All @@ -45,30 +57,34 @@ class topic_data
topic_data(std::string name, bool check_message);
};

class check_message_alive
{
public:
void pmap_stat_alive_callback(const std_msgs::Bool::ConstPtr& msg);
void filtered_points_alive_callback(const sensor_msgs::PointCloud2::ConstPtr& msg);
void ndt_pose_alive_callback(const geometry_msgs::PoseStamped::ConstPtr& msg);
void lane_array_alive_callback(const aslan_msgs::LaneArray::ConstPtr& msg);
void twist_cmd_alive_callback(const geometry_msgs::TwistStamped::ConstPtr& msg);
void twist_raw_alive_callback(const geometry_msgs::TwistStamped::ConstPtr& msg);
void points_raw_alive_callback(const sensor_msgs::PointCloud2::ConstPtr& msg);
void traffic_array_alive_callback(const aslan_msgs::LaneArray::ConstPtr& msg);
void closest_alive_callback(const std_msgs::Int32ConstPtr& msg, VelocitySetPath vs_path);
void final_waypoints_callback(const aslan_msgs::LaneConstPtr& msg);
void current_pose_callback(const geometry_msgs::PoseStampedConstPtr &msg);
void safety_waypoints_callback(const aslan_msgs::LaneConstPtr& msg);
void tf_callback(const tf2_msgs::TFMessageConstPtr &msg);
void radar_emergency_callback(const std_msgs::Int32::ConstPtr& msg);
diagnostic_msgs::DiagnosticStatus get_topic_diagnostics(topic_data topic);
diagnostic_msgs::DiagnosticArray generate_diagnostics();
int RUN(int argc, char **argv);

diagnostic_msgs::DiagnosticArray aslan_diagnostics_array;
diagnostic_msgs::DiagnosticStatus aslan_diagnostics_status;
int seq = 0;
bool tf_msg1 = true, tf_msg2 = true, tf_msg3 = true;
bool emergency_flag = false;
bool end_of_waypoints = false;
void waypointsCallback(const aslan_msgs::LaneConstPtr& msg);


topic_data pmap_stat ("pmap_stat", false);
topic_data filtered_points ("filtered_points", false);
topic_data ndt_pose ("ndt_pose", false);
topic_data lane_waypoints_array ("lane_waypoints_array", false);
topic_data twist_cmd ("twist_cmd", true);
topic_data twist_raw ("twist_raw", false);
topic_data points_raw ("points_raw", true);
topic_data traffic_waypoints_array ("traffic_waypoints_array", false);
topic_data closest_waypoint ("closest_waypoint", false);
topic_data final_waypoints ("final_waypoints", false);
topic_data current_pose ("current_pose", false);
topic_data safety_waypoints ("safety_waypoints", false);
topic_data transf ("tf", true);


diagnostic_msgs::DiagnosticArray aslan_diagnostics_array;
diagnostic_msgs::DiagnosticStatus aslan_diagnostics_status;
int seq = 0;
bool tf_msg1 = true, tf_msg2 = true, tf_msg3 = true;
bool emergency_flag = false;
bool end_of_waypoints = false;
// void waypointsCallback(const aslan_msgs::LaneConstPtr& msg);

int FIXED_ERROR_THRESH = 200; // 200 ms
int FIXED_ERROR_THRESH = 200; // 200 ms
};
41 changes: 41 additions & 0 deletions src/supervisor/check_message_alive/include/error_listener.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
/*
* Copyright (C) 2020 Project ASLAN - All rights reserved
*
* Author: Abdelrahman Barghouth
*
* 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 the copyright holder 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 OWNER 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 <ros/ros.h>
#include <diagnostic_msgs/DiagnosticArray.h>
#include <diagnostic_msgs/DiagnosticStatus.h>

class error_listener
{
public:
void diagnostics_callback(const diagnostic_msgs::DiagnosticArray::ConstPtr& msg);
int RUN(int argc, char **argv);
};
Loading

0 comments on commit cdc43bd

Please sign in to comment.