PX4 Position_Control RC_Remoter引入

2023-05-16

PX4飞控位置环控制中如何引入遥控器的控制量, 本文基于PX4 1.12版本, 相比于之前的版本, 多引入了Flight Task这么一个模块.

省流总结

  1. 遥控器的值通过_flight_tasks.update() -->_velocity_setpoint 通过 _flight_tasks.getPositionSetpoint() --> setpoint 通过_control.updateSetpoint(setpoint) --> vel_sp 通过 PositionControl::_positionController() --> 前馈项
  2. 发布话题 trajectory_setpoint 为其中的setpoint数值
    发布话题vehicle_local_position_setpoint为P-PID计算后的的setpoint速度数值

主要的程序位于mc_pos_control_main.cpp中, 毕竟这个是位置环的主体部分. 每次循环下面的Run()函数

void
MulticopterPositionControl::Run()
{
	if (should_exit()) {
		_local_pos_sub.unregisterCallback();
		exit_and_cleanup();
		return;
	}

	perf_begin(_cycle_perf);

	if (_local_pos_sub.update(&_local_pos)) {

		poll_subscriptions();
		parameters_update(false);

		// set _dt in controllib Block - the time difference since the last loop iteration in seconds
		const hrt_abstime time_stamp_current = hrt_absolute_time();
		setDt((time_stamp_current - _time_stamp_last_loop) / 1e6f);
		_time_stamp_last_loop = time_stamp_current;

		const bool was_in_failsafe = _in_failsafe;
		_in_failsafe = false;

		// activate the weathervane controller if required. If activated a flighttask can use it to implement a yaw-rate control strategy
		// that turns the nose of the vehicle into the wind
		if (_wv_controller != nullptr) {

			// in manual mode we just want to use weathervane if position is controlled as well
			// in mission, enabling wv is done in flight task
			if (_control_mode.flag_control_manual_enabled) {
				if (_control_mode.flag_control_position_enabled && _wv_controller->weathervane_enabled()) {
					_wv_controller->activate();

				} else {
					_wv_controller->deactivate();
				}
			}

			_wv_controller->update(matrix::Quatf(_att_sp.q_d), _states.yaw);
		}

		// an update is necessary here because otherwise the takeoff state doesn't get skiped with non-altitude-controlled modes
		_takeoff.updateTakeoffState(_control_mode.flag_armed, _vehicle_land_detected.landed, false, 10.f,
					    !_control_mode.flag_control_climb_rate_enabled, time_stamp_current);

		// takeoff delay for motors to reach idle speed
		if (_takeoff.getTakeoffState() >= TakeoffState::ready_for_takeoff) {
			// when vehicle is ready switch to the required flighttask
			start_flight_task();

		} else {
			// stop flighttask while disarmed
			_flight_tasks.switchTask(FlightTaskIndex::None);
		}

		// check if any task is active
		if (_flight_tasks.isAnyTaskActive()) {
			// setpoints and constraints for the position controller from flighttask or failsafe
			vehicle_local_position_setpoint_s setpoint = FlightTask::empty_setpoint;
			vehicle_constraints_s constraints = FlightTask::empty_constraints;

			_flight_tasks.setYawHandler(_wv_controller);

			// update task
			if (!_flight_tasks.update()) {
				// FAILSAFE
				// Task was not able to update correctly. Do Failsafe.
				failsafe(setpoint, _states, false, !was_in_failsafe);

			} else {
				setpoint = _flight_tasks.getPositionSetpoint();
				constraints = _flight_tasks.getConstraints();

				_failsafe_land_hysteresis.set_state_and_update(false, time_stamp_current);

				// Check if position, velocity or thrust pairs are valid -> trigger failsaife if no pair is valid
				if (!(PX4_ISFINITE(setpoint.x) && PX4_ISFINITE(setpoint.y)) &&
				    !(PX4_ISFINITE(setpoint.vx) && PX4_ISFINITE(setpoint.vy)) &&
				    !(PX4_ISFINITE(setpoint.thrust[0]) && PX4_ISFINITE(setpoint.thrust[1]))) {
					failsafe(setpoint, _states, true, !was_in_failsafe);
				}

				// Check if altitude, climbrate or thrust in D-direction are valid -> trigger failsafe if none
				// of these setpoints are valid
				if (!PX4_ISFINITE(setpoint.z) && !PX4_ISFINITE(setpoint.vz) && !PX4_ISFINITE(setpoint.thrust[2])) {
					failsafe(setpoint, _states, true, !was_in_failsafe);
				}
			}

			// publish trajectory setpoint
			_traj_sp_pub.publish(setpoint);

			landing_gear_s gear = _flight_tasks.getGear();

			// check if all local states are valid and map accordingly
			set_vehicle_states(setpoint.vz);

			// handle smooth takeoff
			_takeoff.updateTakeoffState(_control_mode.flag_armed, _vehicle_land_detected.landed, constraints.want_takeoff,
						    constraints.speed_up, !_control_mode.flag_control_climb_rate_enabled, time_stamp_current);
			constraints.speed_up = _takeoff.updateRamp(_dt, constraints.speed_up);

			if (_takeoff.getTakeoffState() < TakeoffState::rampup && !PX4_ISFINITE(setpoint.thrust[2])) {
				// we are not flying yet and need to avoid any corrections
				reset_setpoint_to_nan(setpoint);
				setpoint.thrust[0] = setpoint.thrust[1] = setpoint.thrust[2] = 0.0f;
				// set yaw-sp to current yaw
				// TODO: we need a clean way to disable yaw control
				setpoint.yaw = _states.yaw;
				setpoint.yawspeed = 0.f;
				// prevent any integrator windup
				_control.resetIntegralXY();
				_control.resetIntegralZ();
				// reactivate the task which will reset the setpoint to current state
				_flight_tasks.reActivate();
			}

			if (_takeoff.getTakeoffState() < TakeoffState::flight && !PX4_ISFINITE(setpoint.thrust[2])) {
				constraints.tilt = math::radians(_param_mpc_tiltmax_lnd.get());
			}

			// limit altitude only if local position is valid
			if (PX4_ISFINITE(_states.position(2))) {
				limit_altitude(setpoint);
			}

			// Update states, setpoints and constraints.
			_control.updateConstraints(constraints);
			_control.updateState(_states);

			// update position controller setpoints
			if (!_control.updateSetpoint(setpoint)) {
				warn_rate_limited("Position-Control Setpoint-Update failed");
				failsafe(setpoint, _states, true, !was_in_failsafe);
				_control.updateSetpoint(setpoint);
				constraints = FlightTask::empty_constraints;
			}

			// Generate desired thrust and yaw.
			_control.generateThrustYawSetpoint(_dt);

			// Fill local position, velocity and thrust setpoint.
			// This message contains setpoints where each type of setpoint is either the input to the PositionController
			// or was generated by the PositionController and therefore corresponds to the PositioControl internal states (states that were generated by P-PID).
			// Example:
			// If the desired setpoint is position-setpoint, _local_pos_sp will contain
			// position-, velocity- and thrust-setpoint where the velocity- and thrust-setpoint were generated by the PositionControlller.
			// If the desired setpoint has a velocity-setpoint only, then _local_pos_sp will contain valid velocity- and thrust-setpoint, but the position-setpoint
			// will remain NAN. Given that the PositionController cannot generate a position-setpoint, this type of setpoint is always equal to the input to the
			// PositionController.
			vehicle_local_position_setpoint_s local_pos_sp{};
			local_pos_sp.timestamp = hrt_absolute_time();
			local_pos_sp.x = setpoint.x;
			local_pos_sp.y = setpoint.y;
			local_pos_sp.z = setpoint.z;
			local_pos_sp.yaw = _control.getYawSetpoint();
			local_pos_sp.yawspeed = _control.getYawspeedSetpoint();
			local_pos_sp.vx = PX4_ISFINITE(_control.getVelSp()(0)) ? _control.getVelSp()(0) : setpoint.vx;
			local_pos_sp.vy = PX4_ISFINITE(_control.getVelSp()(1)) ? _control.getVelSp()(1) : setpoint.vy;
			local_pos_sp.vz = PX4_ISFINITE(_control.getVelSp()(2)) ? _control.getVelSp()(2) : setpoint.vz;
			_control.getThrustSetpoint().copyTo(local_pos_sp.thrust);

			// Publish local position setpoint
			// This message will be used by other modules (such as Landdetector) to determine
			// vehicle intention.
			_local_pos_sp_pub.publish(local_pos_sp);

			// Inform FlightTask about the input and output of the velocity controller
			// This is used to properly initialize the velocity setpoint when onpening the position loop (position unlock)
			_flight_tasks.updateVelocityControllerIO(_control.getVelSp(), Vector3f(local_pos_sp.thrust));

			// Part of landing logic: if ground-contact/maybe landed was detected, turn off
			// controller. This message does not have to be logged as part of the vehicle_local_position_setpoint topic.
			// Note: only adust thrust output if there was not thrust-setpoint demand in D-direction.
			if (_takeoff.getTakeoffState() > TakeoffState::rampup && !PX4_ISFINITE(setpoint.thrust[2])) {
				limit_thrust_during_landing(local_pos_sp);
			}

			// Fill attitude setpoint. Attitude is computed from yaw and thrust setpoint.
			_att_sp = ControlMath::thrustToAttitude(matrix::Vector3f(local_pos_sp.thrust), local_pos_sp.yaw);
			_att_sp.yaw_sp_move_rate = _control.getYawspeedSetpoint();
			_att_sp.fw_control_yaw = false;
			_att_sp.apply_flaps = false;

			// publish attitude setpoint
			// Note: this requires review. The reason for not sending
			// an attitude setpoint is because for non-flighttask modes
			// the attitude septoint should come from another source, otherwise
			// they might conflict with each other such as in offboard attitude control.
			publish_attitude();

			// if there's any change in landing gear setpoint publish it
			if (gear.landing_gear != _old_landing_gear_position
			    && gear.landing_gear != landing_gear_s::GEAR_KEEP) {

				_landing_gear.landing_gear = gear.landing_gear;
				_landing_gear.timestamp = hrt_absolute_time();

				_landing_gear_pub.publish(_landing_gear);
			}

			_old_landing_gear_position = gear.landing_gear;

		} else {
			// no flighttask is active: set attitude setpoint to idle
			_att_sp.roll_body = _att_sp.pitch_body = 0.0f;
			_att_sp.yaw_body = _states.yaw;
			_att_sp.yaw_sp_move_rate = 0.0f;
			_att_sp.fw_control_yaw = false;
			_att_sp.apply_flaps = false;
			matrix::Quatf q_sp = matrix::Eulerf(_att_sp.roll_body, _att_sp.pitch_body, _att_sp.yaw_body);
			q_sp.copyTo(_att_sp.q_d);
			_att_sp.q_d_valid = true;
			_att_sp.thrust_body[2] = 0.0f;

			// reset the numerical derivatives to not generate d term spikes when coming from non-position controlled operation
			_vel_x_deriv.reset();
			_vel_y_deriv.reset();
			_vel_z_deriv.reset();
		}
	}

	perf_end(_cycle_perf);
}

在Position模式中, 程序会在其中的 _flight_tasks.update() 跳转到 对应的子模式 该部分是新增的
程序跳转到FlightTask.cpp中的 bool FlightTasks::update()

bool FlightTasks::update()
{
	_updateCommand();

	if (isAnyTaskActive()) {
		return _current_task.task->updateInitialize() && _current_task.task->update() && _current_task.task->updateFinalize();
	}

	return false;
}

然后会进入到子模式中的更新函数, 比如下面的

bool FlightTaskManualAltitude::updateInitialize()
{
	bool ret = FlightTaskManual::updateInitialize();

	_sub_home_position.update();

	// in addition to manual require valid position and velocity in D-direction and valid yaw
	return ret && PX4_ISFINITE(_position(2)) && PX4_ISFINITE(_velocity(2)) && PX4_ISFINITE(_yaw);
}

继续跳转就可以得到

bool FlightTaskManual::updateInitialize()
{
	bool ret = FlightTask::updateInitialize();

	_sub_manual_control_setpoint.update();

	const bool sticks_available = _evaluateSticks();

	if (_sticks_data_required) {
		ret = ret && sticks_available;
	}

	return ret;
}

以及下面的函数.

bool FlightTaskManual::_evaluateSticks()
{
	hrt_abstime rc_timeout = (_param_com_rc_loss_t.get() * 1.5f) * 1_s;

	/* Sticks are rescaled linearly and exponentially to [-1,1] */
	if ((_time_stamp_current - _sub_manual_control_setpoint.get().timestamp) < rc_timeout) {

		/* Linear scale  */
		_sticks(0) = _sub_manual_control_setpoint.get().x; /* NED x, "pitch" [-1,1] */
		_sticks(1) = _sub_manual_control_setpoint.get().y; /* NED y, "roll" [-1,1] */
		_sticks(2) = -(_sub_manual_control_setpoint.get().z - 0.5f) * 2.f; /* NED z, "thrust" resacaled from [0,1] to [-1,1] */
		_sticks(3) = _sub_manual_control_setpoint.get().r; /* "yaw" [-1,1] */

		/* Exponential scale */
		_sticks_expo(0) = math::expo_deadzone(_sticks(0), _param_mpc_xy_man_expo.get(), _param_mpc_hold_dz.get());
		_sticks_expo(1) = math::expo_deadzone(_sticks(1), _param_mpc_xy_man_expo.get(), _param_mpc_hold_dz.get());
		_sticks_expo(2) = math::expo_deadzone(_sticks(2), _param_mpc_z_man_expo.get(), _param_mpc_hold_dz.get());
		_sticks_expo(3) = math::expo_deadzone(_sticks(3), _param_mpc_yaw_expo.get(), _param_mpc_hold_dz.get());

		// Only switch the landing gear up if the user switched from gear down to gear up.
		// If the user had the switch in the gear up position and took off ignore it
		// until he toggles the switch to avoid retracting the gear immediately on takeoff.
		int8_t gear_switch = _sub_manual_control_setpoint.get().gear_switch;

		if (_gear_switch_old != gear_switch) {
			_applyGearSwitch(gear_switch);
		}

		_gear_switch_old = gear_switch;

		// valid stick inputs are required
		const bool valid_sticks =  PX4_ISFINITE(_sticks(0))
					   && PX4_ISFINITE(_sticks(1))
					   && PX4_ISFINITE(_sticks(2))
					   && PX4_ISFINITE(_sticks(3));

		return valid_sticks;

	} else {
		/* Timeout: set all sticks to zero */
		_sticks.zero();
		_sticks_expo.zero();
		_gear.landing_gear = landing_gear_s::GEAR_KEEP;
		return false;
	}
}

其中上面的函数中可以看出,是对遥控器数据进行读入. 而对应的下面的update函数中含有一个_scaleSticks()则完成数据的转移

bool FlightTaskManualAltitude::update()
{
	_scaleSticks();
	_updateSetpoints();
	_constraints.want_takeoff = _checkTakeoff();

	return true;
}

将上面的_scaleSticks()展开得到

void FlightTaskManualPosition::_scaleSticks()
{
	/* Use same scaling as for FlightTaskManualAltitude */
	FlightTaskManualAltitude::_scaleSticks();

	/* Constrain length of stick inputs to 1 for xy*/
	Vector2f stick_xy(&_sticks_expo(0));

	float mag = math::constrain(stick_xy.length(), 0.0f, 1.0f);

	if (mag > FLT_EPSILON) {
		stick_xy = stick_xy.normalized() * mag;
	}

	// scale the stick inputs
	if (PX4_ISFINITE(_sub_vehicle_local_position.get().vxy_max)) {
		// estimator provides vehicle specific max

		// use the minimum of the estimator and user specified limit
		_velocity_scale = fminf(_constraints.speed_xy, _sub_vehicle_local_position.get().vxy_max);
		// Allow for a minimum of 0.3 m/s for repositioning
		_velocity_scale = fmaxf(_velocity_scale, 0.3f);

	} else if (stick_xy.length() > 0.5f) {
		// raise the limit at a constant rate up to the user specified value

		if (_velocity_scale < _constraints.speed_xy) {
			_velocity_scale += _deltatime * _param_mpc_acc_hor_estm.get();

		} else {
			_velocity_scale = _constraints.speed_xy;

		}
	}

	// scale velocity to its maximum limits
	Vector2f vel_sp_xy = stick_xy * _velocity_scale;

	/* Rotate setpoint into local frame. */
	_rotateIntoHeadingFrame(vel_sp_xy);

	// collision prevention
	if (_collision_prevention.is_active()) {
		_collision_prevention.modifySetpoint(vel_sp_xy, _velocity_scale, Vector2f(_position),
						     Vector2f(_velocity));
	}

	_velocity_setpoint(0) = vel_sp_xy(0);
	_velocity_setpoint(1) = vel_sp_xy(1);
}

至此我们稍微做个总结, 相当于遥控器的值在 FlightTaks::update()中完成读入, 并转化成了_velocity_setpoint()

紧接着 后面有一个函数setpoint = _flight_tasks.getPositionSetpoint(); 我们将其展开得到

const vehicle_local_position_setpoint_s FlightTask::getPositionSetpoint()
{
	/* fill position setpoint message */
	vehicle_local_position_setpoint_s vehicle_local_position_setpoint;
	vehicle_local_position_setpoint.timestamp = hrt_absolute_time();

	vehicle_local_position_setpoint.x = _position_setpoint(0);
	vehicle_local_position_setpoint.y = _position_setpoint(1);
	vehicle_local_position_setpoint.z = _position_setpoint(2);

	vehicle_local_position_setpoint.vx = _velocity_setpoint(0);
	vehicle_local_position_setpoint.vy = _velocity_setpoint(1);
	vehicle_local_position_setpoint.vz = _velocity_setpoint(2);

	vehicle_local_position_setpoint.acc_x = _acceleration_setpoint(0);
	vehicle_local_position_setpoint.acc_y = _acceleration_setpoint(1);
	vehicle_local_position_setpoint.acc_z = _acceleration_setpoint(2);

	vehicle_local_position_setpoint.jerk_x = _jerk_setpoint(0);
	vehicle_local_position_setpoint.jerk_y = _jerk_setpoint(1);
	vehicle_local_position_setpoint.jerk_z = _jerk_setpoint(2);

	_thrust_setpoint.copyTo(vehicle_local_position_setpoint.thrust);
	vehicle_local_position_setpoint.yaw = _yaw_setpoint;
	vehicle_local_position_setpoint.yawspeed = _yawspeed_setpoint;

	return vehicle_local_position_setpoint;
}

可见随后_velocity_setpoint() 进入到setpoint变量中

---------------------! 分割线 !---------------------

随后通过_traj_sp_pub.publish(setpoint);将setpoint以话题的形式发布出去; 话题为trajectory_setpoint

随后 我们注意到下面有一个_control.updateSetpoint(setpoint)函数, 我们将其展开. 来看一下是如何进入到控制中的

bool PositionControl::updateSetpoint(const vehicle_local_position_setpoint_s &setpoint)
{
	// by default we use the entire position-velocity control-loop pipeline (flag only for logging purpose)
	_setCtrlFlag(true);

	_pos_sp = Vector3f(setpoint.x, setpoint.y, setpoint.z);
	_vel_sp = Vector3f(setpoint.vx, setpoint.vy, setpoint.vz);
	_acc_sp = Vector3f(setpoint.acc_x, setpoint.acc_y, setpoint.acc_z);
	_thr_sp = Vector3f(setpoint.thrust);
	_yaw_sp = setpoint.yaw;
	_yawspeed_sp = setpoint.yawspeed;
	bool mapping_succeeded = _interfaceMapping();

	// If full manual is required (thrust already generated), don't run position/velocity
	// controller and just return thrust.
	_skip_controller = PX4_ISFINITE(_thr_sp(0)) && PX4_ISFINITE(_thr_sp(1))
			   && PX4_ISFINITE(_thr_sp(2));

	return mapping_succeeded;
}

此处又将setpoint赋值给 _vel_sp.

位置环P-PID形式在下面函数中完成
_control.generateThrustYawSetpoint(_dt);

void PositionControl::generateThrustYawSetpoint(const float dt)
{
	if (_skip_controller) {

		// Already received a valid thrust set-point.
		// Limit the thrust vector.
		float thr_mag = _thr_sp.length();

		if (thr_mag > _param_mpc_thr_max.get()) {
			_thr_sp = _thr_sp.normalized() * _param_mpc_thr_max.get();

		} else if (thr_mag < _param_mpc_manthr_min.get() && thr_mag > FLT_EPSILON) {
			_thr_sp = _thr_sp.normalized() * _param_mpc_manthr_min.get();
		}

		// Just set the set-points equal to the current vehicle state.
		_pos_sp = _pos;
		_vel_sp = _vel;
		_acc_sp = _acc;

	} else {
		_positionController();
		_velocityController(dt);
	}
}

我们将_positionController()展开

void PositionControl::_positionController()
{
	// P-position controller
	const Vector3f vel_sp_position = (_pos_sp - _pos).emult(Vector3f(_param_mpc_xy_p.get(), _param_mpc_xy_p.get(),
					 _param_mpc_z_p.get()));
	_vel_sp = vel_sp_position + _vel_sp;

	// Constrain horizontal velocity by prioritizing the velocity component along the
	// the desired position setpoint over the feed-forward term.
	const Vector2f vel_sp_xy = ControlMath::constrainXY(Vector2f(vel_sp_position),
				   Vector2f(_vel_sp - vel_sp_position), _param_mpc_xy_vel_max.get());
	_vel_sp(0) = vel_sp_xy(0);
	_vel_sp(1) = vel_sp_xy(1);
	// Constrain velocity in z-direction.
	_vel_sp(2) = math::constrain(_vel_sp(2), -_constraints.speed_up, _constraints.speed_down);
}

可以看到_vel_sp 作为前馈项进入到 速度设定值中

然后通过速度控制PID算出来Thrust 以及 Yaw的方向设定值
发布话题vehicle_local_position_setpoint. 其中速度为P-PID计算后的的setpoint速度数值_vel_sp变量

最后再将三维的Thrust转换为给定的Attitude.

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

PX4 Position_Control RC_Remoter引入 的相关文章

  • 带有位置参数的 Git 别名

    基本上我正在尝试别名 git files 9fa3 执行命令 git diff name status 9fa3 9fa3 但 git 似乎没有将位置参数传递给别名命令 我努力了 alias files git diff name stat
  • 如何在Python中显示列表元素的索引? [复制]

    这个问题在这里已经有答案了 我有以下代码 hey lol hey water pepsi jam for item in hey print item 我是否在项目之前显示列表中的位置 如下所示 1 lol 2 hey 3 water 4
  • Android:以编程方式更改视图的绝对位置

    如果您使用 AbsoluteLayout 我知道它已被弃用 但这是解决我的问题的唯一方法 problem https stackoverflow com questions 3438656 android scrollable horizo
  • 在Python中写入打开的文件时的分割函数[重复]

    这个问题在这里已经有答案了 所以我有一个程序 我应该在其中获取一个外部文件 用 python 打开它 然后分隔每个单词和每个标点符号 包括逗号 撇号和句号 然后我应该将该文件保存为文本中每个单词和标点符号出现时的整数位置 例如 我喜欢编码
  • javascript中div的随机位置

    我正在尝试使用 javascript 使 Div 随机出现在网页上的任何位置 因此 一个 div 出现然后消失 然后另一个 div 出现在页面上的其他位置然后消失 然后另一个 div 再次出现在页面上的另一个随机位置然后消失 依此类推 我不
  • 检索 HTML 元素的位置 (X,Y)

    我想知道如何获取 HTML 元素的 X 和 Y 位置 例如img and div在 JavaScript 中 正确的方法是使用element getBoundingClientRect https developer mozilla org
  • 如何更改Android SeekBar轨道开始位置?

    我想设置SeekBars的轨道起始位置 因此它不会从搜索栏的左侧开始 而是形成任意位置 这是一张 Photoshop 图像 它应该是这样的 http i imgur com QCMEu png https i imgur com QCMEu
  • 以编程方式设置 LinearLayout 的重力

    我已按照说明为 Unity 制作新的 AdMob 插件 广告显示正确 但底部位置有问题 它们显示在屏幕顶部 我已将重力设置为底部 对于 FrameLayout 但横幅广告再次显示在屏幕顶部 我没有任何带有 LinearLayout Fram
  • Dojo Dijit 对话框相对位置。是否可以?

    我想将 Dojo 的 Dijit Dialog 相对于我的 html 元素之一定位 是否可以 如果是 如何 目前它总是在视口中间显示对话框 任何人都可以帮助我解决此事吗 Thanks 阿玛尔4金图 我这样做的另一种方法 不是很好 因为我重写
  • Vim 从光标上次消失的位置开始

    如何让 Vim 始终从我上次退出给定文件时所在的行开始 将其放入您的 vimrc 中 When editing a file always jump to the last cursor position au BufReadPost if
  • 在像素着色器中计算世界空间坐标

    我有一个像素着色器 我想根据我的世界空间坐标计算每个像素的位置 我该怎么做 我需要什么 我有一个ps input具有 float4 位置的结构 SV POSITION 我认为这很重要 但存储在里面的值似乎有点有趣 我似乎无法弄清楚它们有什么
  • 数组切片返回 [object Object] 而不是值

    我试图获取特定 div 被删除时的位置 在一些帮助下 我整理了下面的代码 我在最后一点添加了尝试获取特定值 但它只是返回 object Object 而不是 0 0 或 0 120 之类的东西 那么问题是如何从数组中获取实际值 Here h
  • 使用position_dodge绘制geom_segment

    我有一个数据集 其中包含个人随时间的工作地点信息 更具体地说 我有关于个人在特定工作场所工作的时间间隔的信息 library tidyverse library lubridate individual A a id lt c rep A
  • 位置:在reveal.js中固定

    我正在尝试为我的reveal js 演示文稿制作一个标题 使其粘贴在屏幕顶部 标题中的内容在每张幻灯片的基础上都是动态的 因此我必须将标记放置在部分标记内 显然 如果标记位于部分标记内 position fixed 并不能真正在 Revea
  • jquery动画位置百分比

    如何确定百分比位置 document ready function button toggle function slide animate top 100 1000 function slide animate top 0 1000 请建
  • 是否可以在同一个 html 页面中多次使用相对位置?

    我在主页上使用 相对位置 和 绝对位置 我有一个使用上述母版页的页面 并且我尝试在此页面中再次对其他 2 个元素使用 相对位置 和 绝对位置 但该页面中下面的元素 绝对位置 是不是根据其上方的元素放置的 相对位置 而是指母版页中元素的 相对
  • 有哪些 CSS 属性可以让元素脱离正常流程?

    有哪些 CSS 属性可以让元素脱离正常流程 这些属性可以是 float position absolute 等 这个问题涉及正常流程的所有可能的改变 只有以下属性会影响任何给定元素的正常流程 float right left positio
  • 我如何找到字符串中多个子字符串的位置(Python 3.4.3 shell)

    以下代码显示 word 在字符串中出现一次的位置 我如何更改我的代码 以便如果 单词 在字符串中出现多次 它将打印所有位置 string input Please input a sentence word input Please inp
  • 可滚动Div,哪些元素可以看到

    我们有一个带有 CSS 的可滚动 divhieght 40px 里面有多个LIheight 20px div li title I1 item1 li li title I2 item2 li li title I3 item3 li li
  • 为什么 ion-fab-button 没有固定在 ionic 4 popover 内?

    我正在开发一个 ionic 4 应用程序 并且创建了一个弹出窗口 在这个弹出窗口中我想使用ion fub button它必须固定在弹出窗口的右上角位置 我写的 HTML 代码是这样的

随机推荐

  • ArduPilot飞行前检查——PreArm解析

    ArduPilot飞行前检查 主要包括两个部分 1 初始化中遥控器输入检查 xff1b 2 1Hz解锁前检查 附 xff1a 显示地面站信息 参考文章 xff1a Ardupilot Pre Arm安全检查程序分析 1 初始化中遥控器输入检
  • ROS_PX4_gazebo学习记录

    在官方程序上 xff08 PX4 wiki上为offboard起飞到2m高度 xff09 进行更改 xff0c 实现首先起飞到固定点 xff08 x 61 1 y 61 2 z 61 5 然后按照给定角度飞行 补充 xff1a 最终实现效果
  • Rospy初次使用记录-定点飞行

    由于接触到pytorch xff0c 所以用python完成与ROS的通信 xff0c 下面例子为从程序中摘出来的一部分 xff0c 用到了ROS消息的订阅与发布 xff0c 服务的通信 xff0c 可以作为参考使用 xff1a span
  • 四旋翼飞行器数学模型

    最近接触到四旋翼无人机的位置控制方法 xff0c 就又了解了一下四旋翼飞机的数学模型 xff0c 现总结如下 xff1a 位置环 xff08 均定义在惯性坐标系下 xff09 P
  • 基于ROS与optitrack的四旋翼飞机开发流程

    本文将一些注意点记录下来 xff0c 适合于开发调试 xff1a 目前只是分段调试通了 xff0c 带后续联合开发的时候在来补充还有没有什么注意点 xff08 过程也算麻烦 xff0c 也算不麻烦 xff09 xff1b xff32 xff
  • ROS_调试(三) 打印输出

    ROS INFO 采用类似C语言的形式 ROS DEBUG ROS DEBUG STREAM 采用类似C 43 43 语言的形式打印 ROS DEBUG STREAM NAMED ROS DEBUG STREAM THROTTLE NAME
  • px4调试bug--添加mavlink_log_info信息

    写在前面的话 有一阵子没有看px4的代码了 由于项目和论文的需要 又要接触这个 其中又遇到一些新的问题 找到了一些新的解决方法 故在此记录一下 总是在几种飞控代码之间跳来跳去 没有认真研究一个 有点遗憾 PX4的代码调试还没有找到什么好的方
  • APM,PX4之开源协议

    APM代码设计的是GPLv3协议 xff0c PX4代码采用的是BSD协议 从上图可以看出 xff0c ardupilot的代码是允许别人修改 xff0c 但是修改之后必须开源且采用相同的许可证书 而PX4代码则是允许别人修改 xff0c
  • C语言实现mavlink库与px4通信仿真

    参照网址 http mavlink io en mavgen c 首先从github上下载对应的C uart interface example 对应的github仓库网址为https github com mavlink c uart i
  • RK3308--8声道改成双声道+录音增益

    改为双声道 修改dts文件 相关路径 xff1a Y hxy RK3308 sdk 1 5 kernel arch arm64 boot dts rockchipY hxy RK3308 sdk 1 5 kernel Documentati
  • Flightmare install 安装指南

    flightmare 是ETH推出的一个用于gazebo仿真 xff0c 强化学习训练的平台 xff0c 并在github上公开了其源代码 本文主要记录在配置环境过程中出现的问题 github网址链接 https github com uz
  • matlab发送mavlink消息

    主要介绍了通过matlab脚本实现UDP发送mavlink消息 xff0c 为后面matlab计算 xff0c 与Optitrack联合调试 xff0c 控制无人机做准备 示例演示效果链接为 matlab通过UDP协议发送mavlink消息
  • apm-ros-optitrack初步尝试

    本文记录采用ArduPilot固件 xff0c 室内optitrack环境下飞行实现中遇到的一些问题 在apm mavros仿真中 xff0c 总是出现mavros state 显示 not connected 在实际的操作中 xff0c
  • APM代码调试知识点汇总

    由于项目的需要 xff0c 对ardupilot的源码进行二次开发 本文记录在二次开发中遇到的问题以及注意事项 xff1a CUAV V5 实测 apm 串口 xff0c 对于姿态数据的发送和接收在200Hz的时候 xff0c 是没有问题的
  • ardupilot之mavlink消息--从飞控发出--单向

    飞控采用mavlink消息进行数据的传输 普遍说法是 xff0c 现有的mavlink消息几乎已经涵盖了所有你的能想象到的内容 xff0c 完全可以覆盖多处需求 无奈科研总是要定义一些新鲜玩意 xff0c 所以总是有无法完全满足需求 xff
  • ardupilot之mavlink消息--飞控接收--单向

    由于项目需要 xff0c 完成一个测试demo 本次从dronekit中发送mavlink消息给飞控 xff0c 飞控接收发来的wp信息 xff0c 然后进行修改供程序使用 首先祭出测试视频 dronekit arudpilot test
  • ArduPilot 添加自定义调节参数

    实际变成操作中 xff0c 需要对ardupilot代码进行修改并添加对应的调试参数 xff0c 这样 xff0c 可以通过地面站很方便的进行修改参数 目前修改代码在parameter h中的G2类 xff0c 表示为全局的参数列表 参数类
  • Python_mavros_manual_contoller

    利用python完成mavros与PX4的通信工程 xff0c 同时也完成了对应的PX4中对应消息代码的调试查看 span class token keyword from span future span class token keyw
  • PX4 混控部分分析

    PX4的混控部分大体思路和ardupilot是一致的 更多的PX4采用的是脚本读取的形式完成其中的读取 转换以及最后的应用 首先从机型选择后 对应为toml文件 如下图所示 采用对应的px generate mixers py来自动生成对应
  • PX4 Position_Control RC_Remoter引入

    PX4飞控位置环控制中如何引入遥控器的控制量 本文基于PX4 1 12版本 相比于之前的版本 多引入了Flight Task这么一个模块 省流总结 遥控器的值通过 flight tasks update gt velocity setpoi