Compare commits

...

3 Commits

Author SHA1 Message Date
cesar f39d7c993d Fixing conflicts 2022-09-16 14:20:10 -03:00
cesar 6fe911a64a removing mocap files - not relevant to Spiri 2022-09-16 14:03:21 -03:00
cesar 4d7bba57ea removing mocap files - Not relavent to spiri 2022-09-16 12:21:27 -03:00
3 changed files with 7 additions and 11 deletions

1
.gitignore vendored
View File

@ -16,3 +16,4 @@ msg/Markers.msg
*.rviz
setup.txt
px4_setup/protobuf_install.txt

View File

@ -84,17 +84,11 @@ target_link_libraries(pathFollow_node ${catkin_LIBRARIES})
add_dependencies(pathFollow_node ${${PROJECT_NAME}EXPORTEDTARGETS} ${catkin_EXPORTED_TARGETS})
#add_dependencies(pathFollow_node oscillation_ctrl_generate_messages_cpp)
#add_executable(mocap_offb_node src/mocap_offb_node.cpp)
add_executable(mocap_pathFollow_node src/mocap_path_follow.cpp)
#target_link_libraries(mocap_offb_node ${catkin_LIBRARIES})
target_link_libraries(mocap_pathFollow_node ${catkin_LIBRARIES})
#add_dependencies(mocap_offb_node ${${PROJECT_NAME}EXPORTEDTARGETS} ${catkin_EXPORTED_TARGETS})
#add_executable(mocap_pathFollow_node src/mocap_path_follow.cpp)
#target_link_libraries(mocap_pathFollow_node ${catkin_LIBRARIES})
#add_dependencies(mocap_pathFollow_node ${${PROJECT_NAME}EXPORTEDTARGETS} ${catkin_EXPORTED_TARGETS})
add_dependencies(mocap_pathFollow_node ${${PROJECT_NAME}EXPORTEDTARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ library
# add_library(${PROJECT_NAME}

View File

@ -15,7 +15,7 @@ import rosservice
from tf.transformations import *
from scipy.integrate import odeint
from oscillation_ctrl.msg import RefSignal, LoadAngles, TetheredStatus
from oscillation_ctrl.msg import RefSignal, LoadAngles
from oscillation_ctrl.srv import WaypointTrack
from geometry_msgs.msg import Pose, Point, TwistStamped, PoseStamped
from sensor_msgs.msg import Imu
@ -185,7 +185,8 @@ class Main:
if rospy.has_param('status/hover_throttle'):
hover_throttle = rospy.get_param('status/hover_throttle')
else:
hover_throttle = (self.tot_m*9.81 + 9.57)/34.84 # linear scaling depending on dependent on mass
hover_throttle = (self.tot_m*9.81 + 11.2)/34.84 # linear scaling depending on dependent on mass
rospy.set_param('status/hover_throttle',hover_throttle)
kf = hover_throttle/(self.tot_m*9.81)
return kf