Commit c2e326c8 authored by Larkin Heintzman's avatar Larkin Heintzman

plaths last flight push

parent 9325d37e
...@@ -111,7 +111,8 @@ ServiceAck obtainCtrlAuthority(); ...@@ -111,7 +111,8 @@ ServiceAck obtainCtrlAuthority();
bool takeoff(); bool takeoff();
std::vector<float> relativePosition(float x, float y, float z, float yaw); void relativeVelocity(float x, float y, float z, float yaw, float dt);
void relativePosition(float x, float y, float z, float yaw, float dt);
float applyRotationAngle(float targetYaw); float applyRotationAngle(float targetYaw);
...@@ -136,7 +137,17 @@ bool overwatchFunction(dji_osdk_ros::Overwatch::Request &req, dji_osdk_ros::Over ...@@ -136,7 +137,17 @@ bool overwatchFunction(dji_osdk_ros::Overwatch::Request &req, dji_osdk_ros::Over
void gpsPosCallback(const sensor_msgs::NavSatFix::ConstPtr& msg); void gpsPosCallback(const sensor_msgs::NavSatFix::ConstPtr& msg);
void posFeedbackCallback(const geometry_msgs::Transform::ConstPtr& msg); void posFeedbackCallback(const geometry_msgs::Transform::ConstPtr& msg);
void pdPositionCallback(const geometry_msgs::Transform::ConstPtr& msg);
void posTrackingCallback(const geometry_msgs::Transform::ConstPtr& msg); void posTrackingCallback(const geometry_msgs::Transform::ConstPtr& msg);
void pdMaxSpeedCallback(const std_msgs::Float32::ConstPtr& msg);
void pdMaxYawSpeedCallback(const std_msgs::Float32::ConstPtr& msg);
void pdSpeedScaleCallback(const std_msgs::Float32::ConstPtr& msg);
void pdUpdateRateCallback(const std_msgs::Float32::ConstPtr& msg);
void pdDampingRateCallback(const std_msgs::Float32::ConstPtr& msg);
void pdFrequencyRateCallback(const std_msgs::Float32::ConstPtr& msg);
void pdAngleOffsetRateCallback(const std_msgs::Float32::ConstPtr& msg);
#endif // MISSION_NODE_H #endif // MISSION_NODE_H
...@@ -14,8 +14,8 @@ def callback(data): ...@@ -14,8 +14,8 @@ def callback(data):
# we must remapp # we must remapp
#transform.translation = data.pose.position #transform.translation = data.pose.position
transform.translation.x = data.pose.position.x transform.translation.x = data.pose.position.x
transform.translation.y = data.pose.position.z transform.translation.y = data.pose.position.y
transform.translation.z = data.pose.position.y transform.translation.z = data.pose.position.z
pub.publish(transform) pub.publish(transform)
......
#!/usr/bin/python3
import rospy
import numpy as np
from sensor_msgs.msg import NavSatFix
from sensor_msgs.msg import Imu
from std_msgs.msg import Float32
from geometry_msgs.msg import PointStamped
from geometry_msgs.msg import QuaternionStamped
from geometry_msgs.msg import Transform
from geometry_msgs.msg import Vector3
from geometry_msgs.msg import Quaternion
import math
from pyproj import Transformer
class QualisysSpoof():
def __init__(self):
rospy.init_node("qualisysSpoof")
# zero zero of fake qualisys frame
self.anchorPoint = rospy.get_param("~anchorPoint")
rospy.Subscriber("dji_osdk_ros/gps_position", NavSatFix, self.gpsCallback, queue_size = 1)
rospy.Subscriber("dji_osdk_ros/attitude", QuaternionStamped, self.rotCallback, queue_size = 1)
# rospy.Subscriber("dji_osdk_ros/height_above_takeoff", Float32, self.heightCallback, queue_size = 1)
# standing in for the feedback qualisys stream
self.posePublisher = rospy.Publisher("feedback", Transform, queue_size = 1)
self.quat = Quaternion()
self.transform = Transform()
self.startHeightSet = False
self.startHeight = 0.0
# self.height = 0.0
def point_rotation(self, origin, pt, ang):
# returns the pt rotated about the origin by ang (ang in degrees)
c = math.cos(math.radians(ang))
s = math.sin(math.radians(ang))
# translate to origin
pt_temp = [pt[0] - origin[0], pt[1] - origin[1]]
pt_spun = [ pt_temp[0]*c - pt_temp[1]*s, pt_temp[0]*s + pt_temp[1]*c ]
# translate back to frame
pt_spun = [pt_spun[0] + origin[0], pt_spun[1] + origin[1]]
return pt_spun
def meters2lat_lon(self, meters_point):
# returns point converted to lat lon from meters coordinate system
transformer = Transformer.from_crs(3857, 4326)
latlon_point = transformer.transform(meters_point[0], meters_point[1])
return latlon_point
def lat_lon2meters(self, latlon_point):
# returns point converted to meters from lat lon coordinate system
transformer = Transformer.from_crs(4326, 3857)
meters_point = transformer.transform(latlon_point[0], latlon_point[1])
return meters_point
def rotCallback(self, data):
self.quat = data.quaternion
def gpsCallback(self, data):
# convert and compare against home point
apMeters = self.lat_lon2meters([self.anchorPoint[0], self.anchorPoint[1]])
cpMeters = self.lat_lon2meters([data.latitude, data.longitude])
currentOffset = [cpMeters[0] - apMeters[0], cpMeters[1] - apMeters[1]]
# rotate current offset by a bit
currentOffset = self.point_rotation([0,0], currentOffset, rospy.get_param("~angleOffset"));
# save init height
if (not self.startHeightSet):
self.startHeightSet = True
self.startHeight = data.altitude
# performing dark magics
self.transform.translation.x = currentOffset[1]
self.transform.translation.y = currentOffset[0]
self.transform.translation.z = data.altitude - self.startHeight
self.transform.rotation = self.quat
self.posePublisher.publish(self.transform)
if __name__ == '__main__':
qualer = QualisysSpoof()
rospy.spin()
...@@ -516,7 +516,7 @@ bool VehicleNode::initDataSubscribeFromFC() ...@@ -516,7 +516,7 @@ bool VehicleNode::initDataSubscribeFromFC()
int nTopic100Hz = topicList100Hz.size(); int nTopic100Hz = topicList100Hz.size();
if (ptr_wrapper_->initPackageFromTopicList(static_cast<int>(SubscribePackgeIndex::PACKAGE_ID_100HZ), nTopic100Hz, if (ptr_wrapper_->initPackageFromTopicList(static_cast<int>(SubscribePackgeIndex::PACKAGE_ID_100HZ), nTopic100Hz,
topicList100Hz.data(), 1, 100)) topicList100Hz.data(), 1, 50))
{ {
ack = ptr_wrapper_->startPackage(static_cast<int>(SubscribePackgeIndex::PACKAGE_ID_100HZ), WAIT_TIMEOUT); ack = ptr_wrapper_->startPackage(static_cast<int>(SubscribePackgeIndex::PACKAGE_ID_100HZ), WAIT_TIMEOUT);
if (ACK::getError(ack)) if (ACK::getError(ack))
...@@ -663,8 +663,10 @@ bool VehicleNode::initDataSubscribeFromFC() ...@@ -663,8 +663,10 @@ bool VehicleNode::initDataSubscribeFromFC()
topicList400Hz.push_back(Telemetry::TOPIC_HARD_SYNC); topicList400Hz.push_back(Telemetry::TOPIC_HARD_SYNC);
int nTopic400Hz = topicList400Hz.size(); int nTopic400Hz = topicList400Hz.size();
// if (ptr_wrapper_->initPackageFromTopicList(static_cast<int>(SubscribePackgeIndex::PACKAGE_ID_400HZ), nTopic400Hz,
// topicList400Hz.data(), 1, 400))
if (ptr_wrapper_->initPackageFromTopicList(static_cast<int>(SubscribePackgeIndex::PACKAGE_ID_400HZ), nTopic400Hz, if (ptr_wrapper_->initPackageFromTopicList(static_cast<int>(SubscribePackgeIndex::PACKAGE_ID_400HZ), nTopic400Hz,
topicList400Hz.data(), 1, 400)) topicList400Hz.data(), 1, 50))
{ {
ack = ptr_wrapper_->startPackage(static_cast<int>(SubscribePackgeIndex::PACKAGE_ID_400HZ), WAIT_TIMEOUT); ack = ptr_wrapper_->startPackage(static_cast<int>(SubscribePackgeIndex::PACKAGE_ID_400HZ), WAIT_TIMEOUT);
if(ACK::getError(ack)) if(ACK::getError(ack))
......
cmake_minimum_required(VERSION 3.0.2)
project(misson_controller)
## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
geometry_msgs
roscpp
rospy
sensor_msgs
std_msgs
)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# geometry_msgs# sensor_msgs# std_msgs
# )
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES misson_controller
# CATKIN_DEPENDS geometry_msgs roscpp rospy sensor_msgs std_msgs
# DEPENDS system_lib
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
# include
${catkin_INCLUDE_DIRS}
)
## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/misson_controller.cpp
# )
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/misson_controller_node.cpp)
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
# ${catkin_LIBRARIES}
# )
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# catkin_install_python(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_misson_controller.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
<?xml version="1.0"?>
<package format="2">
<name>misson_controller</name>
<version>0.0.0</version>
<description>The misson_controller package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="hlarkin3@vt.edu">larkin</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/misson_controller</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_export_depend>geometry_msgs</build_export_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>sensor_msgs</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>std_msgs</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>
cmake_minimum_required(VERSION 3.0.2)
project(puredata)
## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
geometry_msgs
)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# std_msgs
# )
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
INCLUDE_DIRS include
LIBRARIES puredata
CATKIN_DEPENDS roscpp rospy std_msgs geometry_msgs
DEPENDS system_lib
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
# include
${catkin_INCLUDE_DIRS}
)
## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/puredata.cpp
# )
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/puredata_node.cpp)
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
# ${catkin_LIBRARIES}
# )
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# catkin_install_python(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_puredata.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
<?xml version="1.0"?>
<package format="2">
<name>puredata</name>
<version>0.0.0</version>
<description>The puredata package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="hlarkin3@vt.edu">larkin</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/puredata</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<build_export_depend>geometry_msgs</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>
#N canvas 0 96 1013 984 10;
#X obj 54 73 netreceive -u -b;
#X obj 55 98 oscparse;
#X obj 210 23 loadbang;
#X obj 210 56 del 100;
#X obj 55 123 route list;
#X obj 55 159 route sound;
#X obj 121 461 dac~ 1 2;
#X msg 42 279 start;
#X obj 55 211 select 1 0;
#X obj 54 252 t b b;
#X msg 110 273 stop;
#X obj 55 185 route one;
#X obj 121 428 *~;
#X obj 170 427 *~;
#X obj 227 154 route master;
#X obj 215 264 line~;
#X msg 227 182 \$1 100;
#X msg 210 83 \; pd dsp 1;
#X obj 16 202 bng 15 250 50 0 empty empty empty 17 7 0 10 -262144 -1
-1;
#X obj 187 21 bng 15 250 50 0 empty empty empty 17 7 0 10 -262144 -1
-1;
#X obj 95 356 readsf~ 2;
#X obj 175 392 bng 15 250 50 0 empty empty empty 17 7 0 10 -262144
-1 -1;
#X obj 132 160 print oscin;
#X obj 343 387 readsf~ 2;
#X obj 345 429 dac~;
#X obj 317 277 bng 15 250 50 0 empty empty empty 17 7 0 10 -262144
-1 -1;
#X msg 305 356 start;
#X msg 358 362 stop;
#X obj 304 337 bng 15 250 50 0 empty empty empty 17 7 0 10 -262144
-1 -1;
#X obj 355 342 bng 15 250 50 0 empty empty empty 17 7 0 10 -262144
-1 -1;
#X msg 54 49 listen 3722;
#X text 305 261 random testing stuff;
#X floatatom 280 182 5 0 0 0 - - -;
#X obj 53 6 loadbang;
#X text 34 334 need to pick different sounds here;
#X msg 340 305 open ./crushedPiano.wav;
#X obj 54 26 del 500;
#X msg 91 309 open ~/offlinePayload1/payload2-full.aif;
#X connect 0 0 1 0;
#X connect 1 0 4 0;
#X connect 2 0 3 0;
#X connect 3 0 17 0;
#X connect 4 0 5 0;
#X connect 4 0 14 0;
#X connect 4 0 22 0;
#X connect 5 0 11 0;
#X connect 7 0 20 0;
#X connect 8 0 9 0;
#X connect 8 1 10 0;
#X connect 9 0 7 0;
#X connect 9 1 37 0;
#X connect 10 0 20 0;
#X connect 11 0 8 0;
#X connect 12 0 6 0;
#X connect 13 0 6 1;
#X connect 14 0 16 0;
#X connect 14 0 32 0;
#X connect 15 0 12 1;
#X connect 15 0 13 1;
#X connect 16 0 15 0;
#X connect 18 0 9 0;
#X connect 19 0 3 0;
#X connect 20 0 12 0;
#X connect 20 1 13 0;
#X connect 20 2 21 0;
#X connect 23 0 24 0;
#X connect 23 1 24 1;
#X connect 25 0 35 0;
#X connect 26 0 23 0;
#X connect 27 0 23 0;
#X connect 28 0 26 0;
#X connect 29 0 27 0;
#X connect 30 0 0 0;
#X connect 33 0 36 0;
#X connect 35 0 23 0;
#X connect 36 0 30 0;
#X connect 37 0 20 0;
#!/bin/bash
# need to figure out what these audio numbers should be!!
puredata -r 48000 -nogui -audiooutdev 5 -audioindev 5 ../patches/drone-osc.pd
#! /usr/bin/python3
import rospy
import sys
# from osc4py3.as_eventloop import *
# from osc4py3.as_allthreads import *
from osc4py3.as_comthreads import *
from osc4py3 import oscmethod as osm
from geometry_msgs.msg import Transform
from std_msgs.msg import Float32
import netifaces as ni
# blah blah blah
# AHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHH
class OSCTranslator():
def __init__(self):
self.positionPub = rospy.Publisher('pd/target', Transform, queue_size = 1)
self.paramMaxSpeedPub = rospy.Publisher('pd/parameters/maxSpeed', Float32, queue_size = 1)
self.paramMaxYawSpeedPub = rospy.Publisher('pd/parameters/maxYawSpeed', Float32, queue_size = 1)
self.paramSpeedScalePub = rospy.Publisher('pd/parameters/speedScale', Float32, queue_size = 1)
self.paramUpdateRatePub = rospy.Publisher('pd/parameters/updateRate', Float32, queue_size = 1)
self.paramDampingPub = rospy.Publisher('pd/parameters/damping', Float32, queue_size = 1)
self.paramFrequencyPub = rospy.Publisher('pd/parameters/frequency', Float32, queue_size = 1)
self.paramAngleOffsetPub = rospy.Publisher('pd/parameters/angleOffset', Float32, queue_size = 1)
rospy.init_node('puredata_publisher')
self.rate = rospy.Rate(100)
self.target = Transform()
rospy.loginfo("starting osc server")
# Make server channels to receive packets.
# get wifi interfaces ip
# dont listen on the wireless when wanting it through the ethernet~
# osc_udp_server(ni.ifaddresses('wlan0')[ni.AF_INET][0]['addr'], 3721, "aservername")
osc_udp_server(ni.ifaddresses('eth0')[ni.AF_INET][0]['addr'], 3721, "aservername")
osc_method("/position", self.handlerfunctionflex, argscheme=osm.OSCARG_ADDRESS + osm.OSCARG_DATAUNPACK)
osc_method("/parameters", self.handlerfunctionflex, argscheme=osm.OSCARG_ADDRESS + osm.OSCARG_DATAUNPACK)
osc_method("/sound/one", self.handlerfunctionflex, argscheme=osm.OSCARG_ADDRESS + osm.OSCARG_DATAUNPACK)
osc_method("/master", self.handlerfunctionflex, argscheme=osm.OSCARG_ADDRESS + osm.OSCARG_DATAUNPACK)
def handlerfunctionflex(self, address, *args):
# Will receive message data unpacked in s, x, y
rospy.loginfo("from: " + address + ": " + str(args))
if (address == "/position"):
# rospy.loginfo("publishing position...")
self.target.translation.x = args[0]
self.target.translation.y = args[1]
self.target.translation.z = args[2]
self.target.rotation.x = args[3]
self.positionPub.publish(self.target)
elif (address == "/parameters/maxSpeed"):
# rospy.loginfo("new maxSpeed param: " + str(args[0]))
self.paramMaxSpeedPub.publish(args[0])
elif (address == "/parameters/maxYawSpeed"):
# rospy.loginfo("new maxYawSpeed param: " + str(args[0]))
self.paramMaxYawSpeedSpeedPub.publish(args[0])
elif (address == "/parameters/speedScale"):
# rospy.loginfo("new speedScale param: " + str(args[0]))
self.paramSpeedScalePub.publish(args[0])
elif (address == "/parameters/updateRate"):
# rospy.loginfo("new updateRate param: " + str(args[0]))
self.paramUpdateRatePub.publish(args[0])
elif (address == "/parameters/damping"):
# rospy.loginfo("new damping param: " + str(args[0]))
self.paramDampingPub.publish(args[0])
elif (address == "/parameters/frequency"):
# rospy.loginfo("new frequency param: " + str(args[0]))
self.paramFrequencyPub.publish(args[0])
elif (address == "/parameters/angleOffset"):
# rospy.loginfo("new angleOffset param: " + str(args[0]))
self.paramAngleOffsetPub.publish(args[0])
elif (address == "/sound/one"):
rospy.loginfo("publishing sound...")
elif (address == "/master"):
rospy.loginfo("publishing master vol...")
# pure data will handle sounds..?
pass
if __name__ == "__main__":
osc_startup()
oscer = OSCTranslator()
rospy.loginfo("starting osc process loop")
while not rospy.is_shutdown():
# rospy.loginfo("processing osc msgs...")
osc_process()
oscer.rate.sleep()
# rospy.spin()
osc_terminate()
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment