Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[NEW EXERCISE] New drone tello exercise added #2128

Open
wants to merge 1 commit into
base: old_manager
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -17,10 +17,12 @@ Take a look at the [contributing](CONTRIBUTING.md) guide lines.
- [Client side.][] (Robotics Academy architecture)
- [Repository Architecture.][]
- [Generate a mini RADI.][]
- [Humble mini RADI structure.][]
- [Develop using volume binding.][]

[Instructions for developers.]: ./docs/InstructionsForDevelopers.md
[Client side.]: ./docs/clientside.md
[Repository Architecture.]: ./docs/RepositoryArchitecture.md
[Generate a mini RADI.]: ./docs/generate_a_mini_radi.md
[Humble mini RADI structure.]: ./scripts/mini_RADI/README.md
[Develop using volume binding.]: ./docs/develop_binding_volumes.md
Binary file modified db.sqlite3
Binary file not shown.
Binary file not shown.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
import os.path
from typing import Callable

from src.manager.libs.applications.compatibility.exercise_wrapper import CompatibilityExerciseWrapper


class Exercise(CompatibilityExerciseWrapper):
def __init__(self, circuit: str, update_callback: Callable):
current_path = os.path.dirname(__file__)

super(Exercise, self).__init__(exercise_command=f"{current_path}/../python_template/ros1_noetic/exercise.py 0.0.0.0",
gui_command=f"{current_path}/../python_template/ros1_noetic/gui.py 0.0.0.0 {circuit}",
update_callback=update_callback)
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="/RoboticsAcademy/exercises/static/exercises/autoparking_newmanager/launch/ros1_noetic/autoparking.world"/>
<arg name="paused" value="false"/>
<arg name="use_sim_time" value="true"/>
<arg name="gui" value="false"/>
<arg name="headless" value="true"/>
<arg name="debug" value="false"/>
<arg name="verbose" default="true"/>
</include>
</launch>
Original file line number Diff line number Diff line change
@@ -5,28 +5,26 @@
<scene>
<grid>true</grid>
</scene>
<include>
<uri>model://ground_plane</uri>
</include>

<!-- A global light source -->
<include>
<uri>model://sun</uri>
</include>


<!-- A taxi with lasers
<!-- A taxi with lasers-->
<include>
<uri>model://taxi_holo_laser_ROS</uri>
<pose>-7 2.5 0.02 0 0 0</pose>
</include>-->
</include>


<!-- Cars -->
<model name="car1">
<pose>-20 -3 0 0 0 1.57</pose>
<static>true</static>
<static>false</static>
<link name="car1">
<gravity>true</gravity>
<gravity>false</gravity>
<collision name="collision">
<geometry>
<mesh>
@@ -46,9 +44,9 @@

<model name="car2">
<pose>-13.5 -3 0 0 0 1.57</pose>
<static>true</static>
<static>false</static>
<link name="car1">
<gravity>true</gravity>
<gravity>false</gravity>
<collision name="collision">
<geometry>
<mesh>
@@ -68,9 +66,9 @@

<model name="car3">
<pose>-7 -3 0 0 0 1.57</pose>
<static>true</static>
<static>false</static>
<link name="car1">
<gravity>true</gravity>
<gravity>false</gravity>
<collision name="collision">
<geometry>
<mesh>
@@ -90,9 +88,9 @@

<model name="car4">
<pose>0.5 -3 0 0 0 1.57</pose>
<static>true</static>
<static>false</static>
<link name="car1">
<gravity>true</gravity>
<gravity>false</gravity>
<collision name="collision">
<geometry>
<mesh>
@@ -112,9 +110,9 @@

<model name="car5">
<pose>14 -3 0 0 0 1.57</pose>
<static>true</static>
<static>false</static>
<link name="car1">
<gravity>true</gravity>
<gravity>false</gravity>
<collision name="collision">
<geometry>
<mesh>
@@ -134,9 +132,9 @@

<model name="car6">
<pose>21.5 -3 0 0 0 1.57</pose>
<static>true</static>
<static>false</static>
<link name="car1">
<gravity>true</gravity>
<gravity>false</gravity>
<collision name="collision">
<geometry>
<mesh>
@@ -156,9 +154,9 @@

<model name="car7">
<pose>29 -3 0 0 0 1.57</pose>
<static>true</static>
<static>false</static>
<link name="car1">
<gravity>true</gravity>
<gravity>false</gravity>
<collision name="collision">
<geometry>
<mesh>
@@ -205,5 +203,6 @@
</script>
</material>
</road>

</world>
</sdf>
</sdf>
Original file line number Diff line number Diff line change
@@ -2,6 +2,8 @@

from __future__ import print_function

import os

from websocket_server import WebsocketServer
import time
import threading
@@ -186,7 +188,8 @@ def generate_modules(self):
# Add HAL functions
hal_module.HAL.getPose3d = self.hal.pose3d.getPose3d
hal_module.HAL.getFrontLaserData = self.hal.laser_front.getLaserData
hal_module.HAL.getRightLaserData = self.hal.lidar.getLidarData
hal_module.HAL.getRightLaserData = self.hal.laser_right.getLaserData
hal_module.HAL.getBackLaserData = self.hal.laser_back.getLaserData
hal_module.HAL.setV = self.hal.motors.sendV
hal_module.HAL.setW = self.hal.motors.sendW

@@ -371,10 +374,12 @@ def run_server(self):
self.server.set_fn_client_left(self.handle_close)
self.server.set_fn_message_received(self.handle)

home_dir = os.path.expanduser('~')

logged = False
while not logged:
try:
f = open("/ws_code.log", "w")
f = open(f"{home_dir}/ws_code.log", "w")
f.write("websocket_code=ready")
f.close()
logged = True
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
import os
import json
import cv2
import base64
@@ -37,9 +38,11 @@ def __init__(self, host, hal):
t.start()

# Create the map object
laser_object_f = ListenerLaser("/F1ROS/front_laser_points")
pose3d_object = ListenerPose3d("/catvehicle/odom")
self.map = Map(laser_object_f,pose3d_object)
laser_object_f = ListenerLaser("/F1ROS/laser_f/scan")
laser_object_r = ListenerLaser("/F1ROS/laser_r/scan")
laser_object_b = ListenerLaser("/F1ROS/laser_b/scan")
pose3d_object = ListenerPose3d("/F1ROS/odom")
self.map = Map(laser_object_f, laser_object_r, laser_object_b, pose3d_object)

# Explicit initialization function
# Class method, so user can call it without instantiation
@@ -89,10 +92,12 @@ def run_server(self):
self.server.set_fn_new_client(self.get_client)
self.server.set_fn_message_received(self.get_message)

home_dir = os.path.expanduser('~')

logged = False
while not logged:
try:
f = open("/ws_gui.log", "w")
f = open(f"{home_dir}/ws_gui.log", "w")
f.write("websocket_gui=ready")
f.close()
logged = True
Original file line number Diff line number Diff line change
@@ -7,7 +7,7 @@
from interfaces.motors import PublisherMotors
from interfaces.pose3d import ListenerPose3d
from interfaces.laser import ListenerLaser
from interfaces.lidar import ListenerLidar

# Hardware Abstraction Layer
class HAL:
IMG_WIDTH = 320
@@ -16,11 +16,12 @@ class HAL:
def __init__(self):
rospy.init_node("HAL")

self.motors = PublisherMotors("/catvehicle/cmd_vel", 4, 0.3)
self.pose3d = ListenerPose3d("/catvehicle/odom")
self.laser_front = ListenerLaser("/catvehicle/front_laser_points")
self.lidar = ListenerLidar("/catvehicle/lidar_points")

self.motors = PublisherMotors("/taxi_holo/cmd_vel", 4, 0.3)
self.pose3d = ListenerPose3d("/taxi_holo/odom")
self.laser_front = ListenerLaser("/F1ROS/laser_f/scan")
self.laser_right = ListenerLaser("/F1ROS/laser_r/scan")
self.laser_back = ListenerLaser("/F1ROS/laser_b/scan")

# Explicit initialization functions
# Class method, so user can call it without instantiation
@classmethod
@@ -38,6 +39,9 @@ def getPose3d(self):

def getFrontLaserData(self):
return self.laser_front.getLaserData()

def getLidarData(self):
return self.lidar.getLidarData()

def getRightLaserData(self):
return self.laser_right.getLaserData()

def getBackLaserData(self):
return self.laser_back.getLaserData()
Original file line number Diff line number Diff line change
@@ -5,7 +5,7 @@
from interfaces.laser import ListenerLaser

class Map:
def __init__(self, laser_object_f,pose3d_object):
def __init__(self, laser_object_f, laser_object_r, laser_object_b, pose3d_object):
# Car direction
self.carx = 2.0
self.cary = 0.0
@@ -23,6 +23,8 @@ def __init__(self, laser_object_f,pose3d_object):
self.payload = {}

self.laser_topic_f = laser_object_f
self.laser_topic_r = laser_object_r
self.laser_topic_b = laser_object_b
self.pose3d = pose3d_object

# Get the JSON data as string
@@ -79,9 +81,11 @@ def setLaserValues(self):
laser_r = []
laser_b = []
self.laser_f = self.laser_topic_f.getLaserData()
self.laser_r = self.laser_topic_r.getLaserData()
self.laser_b = self.laser_topic_b.getLaserData()

lasers = [self.setSingleLaserValue(self.laser_f)]
ranges = [20 * self.laser_f.maxRange]
lasers = [self.setSingleLaserValue(self.laser_f), self.setSingleLaserValue(self.laser_r), self.setSingleLaserValue(self.laser_b)]
ranges = [20 * self.laser_f.maxRange, 20 * self.laser_r.maxRange, 20 * self.laser_b.maxRange]
return lasers, ranges

# Auxiliar function to setLaserValues
@@ -103,4 +107,4 @@ def setSingleLaserValue(self, laser):
dist = 20 * laser.maxRange
laser_return[i] = (dist, angle)

return laser_return
return laser_return
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
import * as React from "react";
import {Fragment} from "react";

import "./css/AutoparkingRR.css";

const FollowLineRR = (props) => {
return (
<Fragment>
{props.children}
</Fragment>
);
};

export default FollowLineRR;
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
import { paintEvent } from "./map_view";
import React from "react"
import "./css/Lasers.css";
const Lasers = (props) => {
const guiCanvasRef = React.useRef();
React.useEffect(() => {
const callback = (message) => {
if(message.data.update.map){
const map_data = JSON.parse(message.data.update.map);
console.log(JSON.parse(message.data.update.map))
paintEvent(guiCanvasRef.current, map_data.car, map_data.obstacle, map_data.average, map_data.lasers, map_data.ranges)
}
};
RoboticsExerciseComponents.commsManager.subscribe(
[RoboticsExerciseComponents.commsManager.events.UPDATE],
callback
);

return () => {
console.log("TestShowScreen unsubscribing from ['state-changed'] events");
RoboticsExerciseComponents.commsManager.unsubscribe(
[RoboticsExerciseComponents.commsManager.events.UPDATE],
callback
);
};
}, []);
return (
<div style={{
width: "100%",
height: "100%"
}}>
<canvas ref={guiCanvasRef} id="local-map-lasers" width="1280" height="720" ></canvas>
</div>
)
}

export default Lasers;
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
* {
box-sizing: border-box;
}

body, html {
width: 100%; height: 100%;
}

#exercise-container {
position: absolute;
top: 0; left: 0; bottom: 0; right: 0;
overflow: hidden;
display: flex;
flex-direction: column;
}

#exercise-container #content {
width: 100%;
height: 100%;
overflow: hidden;
}

#exercise-container #content #content-exercise {
display: flex;
flex-direction: column;
width: 100%;
height: 100%;
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
#local-map-lasers{
background: #0D488A;
height: 100%;
width: 100%;
}
Loading