static void gst_transcode_bin_set_property (GObject * object, guint prop_id, const GValue * value, GParamSpec * pspec) { GstTranscodeBin *self = GST_TRANSCODE_BIN (object); switch (prop_id) { case PROP_PROFILE: GST_OBJECT_LOCK (self); self->profile = g_value_dup_object (value); GST_OBJECT_UNLOCK (self); break; case PROP_AVOID_REENCODING: GST_OBJECT_LOCK (self); self->avoid_reencoding = g_value_get_boolean (value); GST_OBJECT_UNLOCK (self); break; case PROP_AUDIO_FILTER: _set_filter (self, g_value_dup_object (value), &self->audio_filter); break; case PROP_VIDEO_FILTER: _set_filter (self, g_value_dup_object (value), &self->video_filter); break; default: G_OBJECT_WARN_INVALID_PROPERTY_ID (object, prop_id, pspec); } }
/* update the accel and gyro vectors */ bool AP_InertialSensor_MPU9250::update( void ) { if (!wait_for_sample(1000)) { return false; } _previous_accel[0] = _accel[0]; // pull the data from the timer shared data buffer uint8_t idx = _shared_data_idx; _gyro[0] = _shared_data[idx]._gyro_filtered; _accel[0] = _shared_data[idx]._accel_filtered; _gyro[0].rotate(_board_orientation); _gyro[0] *= GYRO_SCALE; _gyro[0] -= _gyro_offset[0]; _accel[0].rotate(_board_orientation); _accel[0] *= MPU9250_ACCEL_SCALE_1G; // rotate for bbone default _accel[0].rotate(ROTATION_ROLL_180_YAW_90); _gyro[0].rotate(ROTATION_ROLL_180_YAW_90); #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF // PXF has an additional YAW 180 _accel[0].rotate(ROTATION_YAW_180); _gyro[0].rotate(ROTATION_YAW_180); #endif Vector3f accel_scale = _accel_scale[0].get(); _accel[0].x *= accel_scale.x; _accel[0].y *= accel_scale.y; _accel[0].z *= accel_scale.z; _accel[0] -= _accel_offset[0]; if (_last_filter_hz != _mpu6000_filter) { _set_filter(_mpu6000_filter); _last_filter_hz = _mpu6000_filter; } _have_sample_available = false; return true; }
/* update the accel and gyro vectors */ bool AP_InertialSensor_MPU9250::update( void ) { // pull the data from the timer shared data buffer uint8_t idx = _shared_data_idx; Vector3f gyro = _shared_data[idx]._gyro_filtered; Vector3f accel = _shared_data[idx]._accel_filtered; _have_sample_available = false; accel *= MPU9250_ACCEL_SCALE_1G; gyro *= GYRO_SCALE; // rotate for bbone default accel.rotate(ROTATION_ROLL_180_YAW_90); gyro.rotate(ROTATION_ROLL_180_YAW_90); #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF // PXF has an additional YAW 180 accel.rotate(ROTATION_YAW_180); gyro.rotate(ROTATION_YAW_180); #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO // NavIO has different orientation, assuming RaspberryPi is right // way up, and PWM pins on NavIO are at the back of the aircraft accel.rotate(ROTATION_ROLL_180_YAW_90); gyro.rotate(ROTATION_ROLL_180_YAW_90); #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI accel.rotate(ROTATION_ROLL_180); gyro.rotate(ROTATION_ROLL_180); #endif _rotate_and_offset_gyro(_gyro_instance, gyro); _rotate_and_offset_accel(_accel_instance, accel); if (_last_filter_hz != _imu.get_filter()) { _set_filter(_imu.get_filter()); _last_filter_hz = _imu.get_filter(); } return true; }