pennair2 package¶
Subpackages¶
Submodules¶
pennair2.PID module¶
Ivmech PID Controller is simple implementation of a Proportional-Integral-Derivative (PID) Controller in the Python Programming Language. More information about PID Controller: http://en.wikipedia.org/wiki/PID_controller
-
class
pennair2.PID.
PID
(P=0.2, I=0.0, D=0.0)¶ PID Controller
-
clear
()¶ Clears PID computations and coefficients
-
setKd
(derivative_gain)¶ Determines how aggressively the PID reacts to the current error with setting Derivative Gain
-
setKi
(integral_gain)¶ Determines how aggressively the PID reacts to the current error with setting Integral Gain
-
setKp
(proportional_gain)¶ Determines how aggressively the PID reacts to the current error with setting Proportional Gain
-
setSampleTime
(sample_time)¶ PID that should be updated at a regular interval. Based on a pre-determined sampe time, the PID decides if it should compute or return immediately.
-
setWindup
(windup)¶ Integral windup, also known as integrator windup or reset windup, refers to the situation in a PID feedback controller where a large change in setpoint occurs (say a positive change) and the integral terms accumulates a significant error during the rise (windup), thus overshooting and continuing to increase as this accumulated error is unwound (offset by errors in the other direction). The specific problem is the excess overshooting.
-
update
(feedback_value)¶ Calculates PID value for given reference feedback
u(t)=Kpe(t)+Ki∫t0e(t)dt+Kdde/dtTest PID with Kp=1.2, Ki=1, Kd=0.001 (test_pid.py)
-
pennair2.actuation module¶
pennair2.autopilot module¶
-
class
pennair2.autopilot.
Autopilot
¶ Bases:
object
-
global_global
¶ The global position as a GPS coordinate. :return: GPS position. :rtype: NavSatFix
-
global_local
¶ The global position in UTM coordinates. UTM coordinates are used to define position on Earth using a Euclidean coordinate system. :return: Global position in local frame :rtype: PoseWithCovarianceStamped
-
global_velocity_raw
¶ The raw GPS velocity. :return: GPS velocity :rtype: TwistStamped
-
gps_raw
¶ Raw GPS position data. :return: raw GPS data :rtype: NavSatFix
-
gps_twist_raw
¶ Raw GPS velocity data. :return: raw GPS velocity :rtype: TwistStamped
-
imu_data
¶ Returns: Imu data, orientation computed by FCU Return type: Imu
-
imu_raw
¶ Returns: Raw IMU data without orientation Return type: Imu
-
is_connected
()¶
-
local_pose
¶ Fused position in local reference frame, as defined in ~local_position/frame_id :return: Local position :rtype: PoseStamped
-
local_twist
¶ Fused linear and angular velocity from the FCU. :return: velocity :rtype: TwistStamped
-
-
class
pennair2.autopilot.
Mavros
(mavros_prefix='/mavros')¶ Bases:
pennair2.autopilot.Autopilot
-
battery
¶ The status of the battery. This has to be properly configured in QGroundControl to be reliable. :return: Battery status :rtype: BatteryState
-
is_connected
()¶
-
launch_node
(fcu_url='udp://:14540@127.0.0.1:14557', gcs_url='udp://@10.42.0.1', **kwargs)¶ Launch a mavros node corresponding to the appropriate :param fcu_url: The url of the flight control unit. :type fcu_url: str :param gcs_url: The url of the ground station (qGroundControl) for passthrough. :type gcs_url: str :param kwargs: Any other remap arguments.
-
send_command_long
(cmd, params)¶ Send a raw MAVLINK command. :param cmd: The command number. :type cmd: int :param params: A list of parameters to send in the command. :type params: int list :return: A boolean that specifies success and an integer specifying the result. :rtype: (bool, int)
-
state
¶ The state of the autopilot. Includes things like current mode. :return: Mavros state :rtype: State
-
pennair2.controller module¶
-
class
pennair2.controller.
Controller
(quad)¶ Bases:
threading.Thread
-
run
()¶ Method representing the thread’s activity.
You may override this method in a subclass. The standard run() method invokes the callable object passed to the object’s constructor as the target argument, if any, with sequential and keyword arguments taken from the args and kwargs arguments, respectively.
-
pennair2.conversions module¶
Convert GPS to UTM position.
Parameters: - gps – A gps position. If list/tuple given then (longitude, latitude, altitude). Altitude in WSG84.
- force_utm_zone – If not None, then will force utm zone as specified.
-
pennair2.conversions.
feet_to_meters
(feet)¶
-
pennair2.conversions.
gps_to_utm
(gps, force_utm_zone=None)¶ Convert GPS to UTM position. Use NavSatFix_to_PoseStamped for converting between such messages.
Parameters: - gps – List of [latitude, longitude, altitude]
- force_utm_zone – If not None, then will force utm zone as specified.
Returns: UTM position in ENU and the zone number.
-
pennair2.conversions.
knots_to_mets
(knots)¶
-
pennair2.conversions.
meters_to_feet
(meters)¶
-
pennair2.conversions.
meters_to_miles
(meters)¶
-
pennair2.conversions.
mets_to_knots
(mets)¶
-
pennair2.conversions.
miles_to_meters
(miles)¶
-
pennair2.conversions.
to_numpy
(position)¶ Create a numpy array (as a column vector) representation of a geometry_msgs position. :param position: :type position: PoseStamped | PointStamped | Pose | Point | Vector3
-
pennair2.conversions.
to_pose_stamped
(value, frame_id=None, heading=None)¶ Converts a python list / tuple into a PoseStamped message. Specify frame_id and heading if necessary.
Parameters: - value (PoseStamped | Pose | Point | list[int,int,int] | (int,int,int) | np.ndarray) – The desired position setpoint, only yaw component of orientation is used. Can be of type PoseStamped, Pose, Point, or an indexable object with 3 integer elements (list, tuple, numpy array etc.)
- frame_id (str) – The name of the frame to use for the message. Will not override frame_id of PoseStamped.
- heading (int) – Your desired heading in radians. This is the rotation around the z-axis.
pennair2.core module¶
-
class
pennair2.core.
Multirotor
(autopilot, frequency=30)¶ Bases:
pennair2.core.UAV
-
hover
()¶
-
land
(speed=0.5, target=None)¶
-
set_position
(position, frame_id='map', heading=None, blocking=False, margin=0.5)¶ Tells multirotor to fly to maintain given position.
Parameters: - position (PoseStamped | Pose | Point | list[int,int,int] | (int,int,int) | np.ndarray) – The setpoint position.
- frame_id (str) – The frame relative to which the setpoint is set.
- heading (int) – The heading to maintain.
- blocking (bool) – Weather or not to block the thread until setpoint reached.
- margin (float) – The setpoint margin. Only matters if blocking is true.
-
takeoff
(speed=0.5, target_height=10)¶
-
-
class
pennair2.core.
UAV
(autopilot, frequency=30)¶ Bases:
object
-
displacement_from_target
(target=None, current=None, frame_id=None)¶
-
distance_to_target
(target=None, current=None, frame_id=None)¶
-
get_gps
()¶
-
get_heading
()¶
-
get_pose
(utm=False, fmt='pose')¶
-
get_position
(utm=False)¶
-
get_relative_altitude
()¶
-
get_twist
()¶
-
get_velocity
()¶
-
is_armed
¶
-
is_offboard
¶
-
set_position
(value, frame_id='map', heading=None)¶ Parameters: - value (PoseStamped | Pose | Point | list[int,int,int] | (int,int,int) | np.ndarray) – The desired position setpoint, only yaw component of orientation is used. Can be of type PoseStamped, Pose, Point, or an indexable object with 3 integer elements (list, tuple, numpy array etc.)
- frame_id (str) – The name of the frame to use for the message. Will only be applied if value is not already PoseStamped.
- heading (int) – Your desired heading.
-
set_velocity
(value, frame_id=None)¶
-
shutdown
()¶
-
start
()¶
-
transform_pose
(pose, target, timeout=1.0)¶
-
wait
(seconds, rate=30)¶
-
wait_for
(fun, rate=30, wait_val=True)¶
-
pennair2.gui module¶
pennair2.launch module¶
-
class
pennair2.launch.
Node
(name, params)¶ -
add_attribute
(name, value)¶
-
add_param
(name, value)¶
-
add_remap
(old, new)¶
-
add_rosparam
(name, text)¶
-
-
pennair2.launch.
launch
(package, name)¶ API call to roslaunch. Same as command line.
Parameters: - package – The package name.
- name – The name of the launch file
- kwargs – Not implemented in Kinetic. TODO: Implement in Lunar
pennair2.search module¶
-
class
pennair2.search.
BoxSearch
(uav, height=10, radius=None, increment=5)¶ Bases:
pennair2.search.Search
-
run
()¶
-
pennair2.swarm module¶
-
class
pennair2.swarm.
Swarm
¶ -
add_member
(m)¶
-
get_swarm_poses
(origin)¶
-
remove_member
(m)¶
-
set_position
(value, frame_id=None, heading=None)¶ Parameters: - value (PoseStamped | Pose | Point | list[int,int,int] | (int,int,int)) – The desired position setpoint, only yaw component of orientation is used. Can be of type PoseStamped, Pose, Point, or an indexable object with 3 integer elements (list, tuple, numpy array etc.)
- frame_id (str) – The name of the frame to use for the message.
- heading (int) – Your desired heading.
-
Module contents¶
-
class
pennair2.
Controller
(quad)¶ Bases:
threading.Thread
-
run
()¶ Method representing the thread’s activity.
You may override this method in a subclass. The standard run() method invokes the callable object passed to the object’s constructor as the target argument, if any, with sequential and keyword arguments taken from the args and kwargs arguments, respectively.
-
-
class
pennair2.
Multirotor
(autopilot, frequency=30)¶ Bases:
pennair2.core.UAV
-
hover
()¶
-
land
(speed=0.5, target=None)¶
-
set_position
(position, frame_id='map', heading=None, blocking=False, margin=0.5)¶ Tells multirotor to fly to maintain given position.
Parameters: - position (PoseStamped | Pose | Point | list[int,int,int] | (int,int,int) | np.ndarray) – The setpoint position.
- frame_id (str) – The frame relative to which the setpoint is set.
- heading (int) – The heading to maintain.
- blocking (bool) – Weather or not to block the thread until setpoint reached.
- margin (float) – The setpoint margin. Only matters if blocking is true.
-
takeoff
(speed=0.5, target_height=10)¶
-
-
class
pennair2.
Autopilot
¶ Bases:
object
-
global_global
¶ The global position as a GPS coordinate. :return: GPS position. :rtype: NavSatFix
-
global_local
¶ The global position in UTM coordinates. UTM coordinates are used to define position on Earth using a Euclidean coordinate system. :return: Global position in local frame :rtype: PoseWithCovarianceStamped
-
global_velocity_raw
¶ The raw GPS velocity. :return: GPS velocity :rtype: TwistStamped
-
gps_raw
¶ Raw GPS position data. :return: raw GPS data :rtype: NavSatFix
-
gps_twist_raw
¶ Raw GPS velocity data. :return: raw GPS velocity :rtype: TwistStamped
-
imu_data
¶ Returns: Imu data, orientation computed by FCU Return type: Imu
-
imu_raw
¶ Returns: Raw IMU data without orientation Return type: Imu
-
is_connected
()¶
-
local_pose
¶ Fused position in local reference frame, as defined in ~local_position/frame_id :return: Local position :rtype: PoseStamped
-
local_twist
¶ Fused linear and angular velocity from the FCU. :return: velocity :rtype: TwistStamped
-