diff --git a/include/pauvsi_trajectory/Physics.h b/include/pauvsi_trajectory/Physics.h index 4115cbb..bfe378f 100644 --- a/include/pauvsi_trajectory/Physics.h +++ b/include/pauvsi_trajectory/Physics.h @@ -18,6 +18,10 @@ #define MOTOR_FORCE_MIN 1 #define MOTOR_FORCE_MAX 15 +//absolute maximum motor force possible +#define MOTOR_ABS_MAX 25 +#define MOTOR_ABS_MIN 0.1 + //mass of quad kg #define MASS 5 diff --git a/include/pauvsi_trajectory/Simulation.h b/include/pauvsi_trajectory/Simulation.h index 23ed63a..01cfbe7 100644 --- a/include/pauvsi_trajectory/Simulation.h +++ b/include/pauvsi_trajectory/Simulation.h @@ -10,8 +10,8 @@ #define MOTOR_FORCE SIGMA 0.2 #define POSITION_SIGMA 0.03 -#define OMEGA_SIGMA 0.0005 -#define VEL_SIGMA 0.01 +#define OMEGA_SIGMA 0.001 +#define VEL_SIGMA 0.03 #define QUAT_SIGMA 0.001 #define PHYSICS_UPDATE_DT 0.01 @@ -23,10 +23,7 @@ #define BASE_FRAME "base_link" #define WORLD_FRAME "world" -#define START_POS -9, -9, 0.5 - -#define MOTOR_ABS_MAX 25 -#define MOTOR_ABS_MIN 0.1 +#define START_POS -9, -9, 1 diff --git a/launch/simulation.launch b/launch/simulation.launch index c52f6a2..bbf29e9 100644 --- a/launch/simulation.launch +++ b/launch/simulation.launch @@ -1,7 +1,7 @@ - + diff --git a/urdf/m7_robot.urdf b/urdf/m7_robot.urdf deleted file mode 100644 index 8b8e71d..0000000 --- a/urdf/m7_robot.urdf +++ /dev/null @@ -1,154 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - \ No newline at end of file