Skip to content

Commit

Permalink
minor
Browse files Browse the repository at this point in the history
  • Loading branch information
yun-long committed Oct 18, 2020
1 parent 4b8f535 commit 3422752
Show file tree
Hide file tree
Showing 4 changed files with 29 additions and 26 deletions.
1 change: 1 addition & 0 deletions flightlib/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,7 @@ message(STATUS "======> Setup Compilation")

add_definitions(-DEIGEN_STACK_ALLOCATION_LIMIT=1048576)
include_directories(${EIGEN_INCLUDE_DIR} "tests")
include_directories(${OpenCV_INCLUDE_DIRS})

# Set default build type
if (NOT EXISTS ${CMAKE_BINARY_DIR}/CMakeCache.txt)
Expand Down
24 changes: 12 additions & 12 deletions flightlib/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -106,15 +106,15 @@ def build_extension(self, ext):
zip_safe=False,
)

# setup(name='flightgym',
# version='0.0.1',
# author="Yunlong Song",
# author_email='[email protected]',
# description="Flightmare: A Quadrotor Simulator",
# long_description='',
# packages=[''],
# package_dir={'': './build/'},
# package_data={'': ['flightgym.cpython-36m-x86_64-linux-gnu.so']},
# zip_fase=True,
# url=None,
# )
setup(name='flightgym',
version='0.0.1',
author="Yunlong Song",
author_email='[email protected]',
description="Flightmare: A Quadrotor Simulator",
long_description='',
packages=[''],
package_dir={'': './build/'},
package_data={'': ['flightgym.cpython-36m-x86_64-linux-gnu.so']},
zip_fase=True,
url=None,
)
2 changes: 2 additions & 0 deletions flightlib/tests/envs/quadrotor_env/quadrotor_env.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@ TEST(QuadrotorEnv, Constructor) {
logger.info("Environment configuration path \"%s\".", config_path.c_str());
QuadrotorEnv env0(config_path);

Vector<3> debug{3.0, 3.0, 3.0};

// check observation and action dimensions
int obs_dim = env0.getObsDim();
int act_dim = env0.getActDim();
Expand Down
28 changes: 14 additions & 14 deletions flightros/launch/rotors_gazebo.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="model" value="$(find rotors_description)/urdf/mav_generic_odometry_sensor.gazebo"/>
<arg name="world_name" default="$(find rotors_gazebo)/worlds/basic.world"/>

<arg name="use_unity_editor" default="true" />
<arg name="use_unity_editor" default="false" />
<arg name="paused" value="true"/>
<arg name="gui" value="true"/>
<arg name="use_mpc" default="false"/>
Expand All @@ -23,13 +23,13 @@

<arg name="debug" default="false"/>
<arg name="verbose" default="false"/>

<param name="use_sim_time" value="true"/>

<!-- Gazebo stuff to spawn the world !-->
<env name="GAZEBO_MODEL_PATH"
<env name="GAZEBO_MODEL_PATH"
value="${GAZEBO_MODEL_PATH}:$(find rotors_gazebo)/models:$(arg custom_models)"/>
<env name="GAZEBO_RESOURCE_PATH"
<env name="GAZEBO_RESOURCE_PATH"
value="${GAZEBO_RESOURCE_PATH}:$(find rotors_gazebo)/models"/>
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(arg world_name)" />
Expand All @@ -56,7 +56,7 @@
<group ns="$(arg quad_name)" >

<!-- RPG RotorS interface. -->
<node pkg="rpg_rotors_interface" type="rpg_rotors_interface"
<node pkg="rpg_rotors_interface" type="rpg_rotors_interface"
name="rpg_rotors_interface" output="screen" >
<rosparam file="$(find rpg_rotors_interface)/parameters/rpg_rotors_interface.yaml" />
<!-- .. -->
Expand All @@ -73,14 +73,14 @@
<rosparam file="$(find state_predictor)/parameters/hummingbird.yaml" />
<rosparam file="$(find rpg_rotors_interface)/parameters/position_controller.yaml" />
<rosparam file="$(find rpg_rotors_interface)/parameters/autopilot.yaml" />

<param name="position_controller/use_rate_mode" value="True" />

<param name="velocity_estimate_in_world_frame" value="false" />
<param name="state_estimate_timeout" value="0.1" />
<param name="control_command_delay" value="0.05" />
<param name="enable_command_feedthrough" value="$(arg enable_command_feedthrough)" />

<remap from="autopilot/state_estimate" to="ground_truth/odometry" />
</node>

Expand All @@ -100,23 +100,23 @@
</group>

<node pkg="flightros" type="flight_pilot_node" name="flight_pilot_node" output="screen">
<rosparam file="$(find flightros)/params/default.yaml" />
<rosparam file="$(find flightros)/params/default.yaml" />
<remap from="flight_pilot/state_estimate" to="ground_truth/odometry" />
</node>

<node pkg="joy" type="joy_node" name="joy_node">
<param name="autorepeat_rate" value="10"/>
</node>

<node pkg="manual_flight_assistant" type="manual_flight_assistant"
<node pkg="manual_flight_assistant" type="manual_flight_assistant"
name="manual_flight_assistant" output="screen">
<rosparam file="$(find rpg_rotors_interface)/parameters/manual_flight_assistant.yaml"/>
</node>

<node name="rqt_quad_gui" pkg="rqt_gui" type="rqt_gui"
args="-s rqt_quad_gui.basic_flight.BasicFlight --args
<node name="rqt_quad_gui" pkg="rqt_gui" type="rqt_gui"
args="-s rqt_quad_gui.basic_flight.BasicFlight --args
--quad_name $(arg quad_name)" output="screen"/>

</group>
</group>

</launch>
</launch>

0 comments on commit 3422752

Please sign in to comment.