mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-18 22:39:05 +08:00
manual input: deadzones
This commit is contained in:
parent
530c38b6fa
commit
48b781ca3d
@ -48,22 +48,28 @@ ManualInput::ManualInput() :
|
||||
_joy_sub(_n.subscribe("joy", 1, &ManualInput::JoyCallback, this)),
|
||||
_man_ctrl_sp_pub(_n.advertise<px4::manual_control_setpoint>("manual_control_setpoint", 1))
|
||||
{
|
||||
double dz_default = 0.2;
|
||||
/* Load parameters, default values work for Microsoft XBox Controller */
|
||||
_n.param("map_x", _param_axes_map[0], 4);
|
||||
_n.param("scale_x", _param_axes_scale[0], 1.0);
|
||||
_n.param("off_x", _param_axes_offset[0], 0.0);
|
||||
_n.param("dz_x", _param_axes_dz[0], dz_default);
|
||||
|
||||
_n.param("map_y", _param_axes_map[1], 3);
|
||||
_n.param("scale_y", _param_axes_scale[1], -1.0);
|
||||
_n.param("off_y", _param_axes_offset[1], 0.0);
|
||||
_n.param("dz_y", _param_axes_dz[1], dz_default);
|
||||
|
||||
_n.param("map_z", _param_axes_map[2], 2);
|
||||
_n.param("scale_z", _param_axes_scale[2], -0.5);
|
||||
_n.param("off_z", _param_axes_offset[2], 0.5);
|
||||
_n.param("off_z", _param_axes_offset[2], -1.0);
|
||||
_n.param("dz_z", _param_axes_dz[2], dz_default);
|
||||
|
||||
_n.param("map_r", _param_axes_map[3], 0);
|
||||
_n.param("scale_r", _param_axes_scale[3], -1.0);
|
||||
_n.param("off_r", _param_axes_offset[3], 0.0);
|
||||
_n.param("dz_r", _param_axes_dz[3], dz_default);
|
||||
|
||||
}
|
||||
|
||||
void ManualInput::JoyCallback(const sensor_msgs::JoyConstPtr& msg)
|
||||
@ -72,10 +78,10 @@ void ManualInput::JoyCallback(const sensor_msgs::JoyConstPtr& msg)
|
||||
|
||||
/* Fill px4 manual control setpoint topic with contents from ros joystick */
|
||||
/* Map sticks to x, y, z, r */
|
||||
MapAxis(msg, _param_axes_map[0], _param_axes_scale[0], _param_axes_offset[0], msg_out.x);
|
||||
MapAxis(msg, _param_axes_map[1], _param_axes_scale[1], _param_axes_offset[1], msg_out.y);
|
||||
MapAxis(msg, _param_axes_map[2], _param_axes_scale[2], _param_axes_offset[2], msg_out.z);
|
||||
MapAxis(msg, _param_axes_map[3], _param_axes_scale[3], _param_axes_offset[3], msg_out.r);
|
||||
MapAxis(msg, _param_axes_map[0], _param_axes_scale[0], _param_axes_offset[0], _param_axes_dz[0], msg_out.x);
|
||||
MapAxis(msg, _param_axes_map[1], _param_axes_scale[1], _param_axes_offset[1], _param_axes_dz[1], msg_out.y);
|
||||
MapAxis(msg, _param_axes_map[2], _param_axes_scale[2], _param_axes_offset[2], _param_axes_dz[2], msg_out.z);
|
||||
MapAxis(msg, _param_axes_map[3], _param_axes_scale[3], _param_axes_offset[3], _param_axes_dz[3], msg_out.r);
|
||||
//ROS_INFO("x: %1.4f y: %1.4f z: %1.4f r: %1.4f", msg_out.x, msg_out.y, msg_out.z, msg_out.r);
|
||||
|
||||
/* Map buttons to switches */
|
||||
@ -93,9 +99,13 @@ void ManualInput::JoyCallback(const sensor_msgs::JoyConstPtr& msg)
|
||||
_man_ctrl_sp_pub.publish(msg_out);
|
||||
}
|
||||
|
||||
void ManualInput::MapAxis(const sensor_msgs::JoyConstPtr& msg, int map_index, double scale, double offset, float &out)
|
||||
void ManualInput::MapAxis(const sensor_msgs::JoyConstPtr& msg, int map_index, double scale, double offset,
|
||||
double deadzone, float &out)
|
||||
{
|
||||
out = (float)(msg->axes[map_index] * scale + offset);
|
||||
double val = msg->axes[map_index];
|
||||
if (val + offset > deadzone || val + offset < -deadzone) {
|
||||
out = (float)((val + offset)) * scale;
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc, char **argv)
|
||||
|
||||
@ -56,7 +56,8 @@ protected:
|
||||
/**
|
||||
* Helper function to map and scale joystick input
|
||||
*/
|
||||
void MapAxis(const sensor_msgs::JoyConstPtr& msg, int map_index, double scale, double offset, float &out);
|
||||
void MapAxis(const sensor_msgs::JoyConstPtr& msg, int map_index, double scale, double offset, double deadzone,
|
||||
float &out);
|
||||
|
||||
ros::NodeHandle _n;
|
||||
ros::Subscriber _joy_sub;
|
||||
@ -66,6 +67,7 @@ protected:
|
||||
int _param_axes_map[4];
|
||||
double _param_axes_scale[4];
|
||||
double _param_axes_offset[4];
|
||||
double _param_axes_dz[4];
|
||||
|
||||
|
||||
};
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user