aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-12-31 09:19:57 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-12-31 09:19:57 +0100
commitf8214f3e0162fcbd0ca9382b0d00bdab2f5863ee (patch)
tree2b20eea63db4401c4fbb8bb7a25f4249e9d31077
parentbc5fe30270d450ae6e22f69b2fd6b7ff252e8bb1 (diff)
downloadpx4-firmware-f8214f3e0162fcbd0ca9382b0d00bdab2f5863ee.tar.gz
px4-firmware-f8214f3e0162fcbd0ca9382b0d00bdab2f5863ee.tar.bz2
px4-firmware-f8214f3e0162fcbd0ca9382b0d00bdab2f5863ee.zip
manual input fix variable names
-rw-r--r--src/platforms/ros/nodes/manual_input/manual_input.cpp34
-rw-r--r--src/platforms/ros/nodes/manual_input/manual_input.h8
2 files changed, 21 insertions, 21 deletions
diff --git a/src/platforms/ros/nodes/manual_input/manual_input.cpp b/src/platforms/ros/nodes/manual_input/manual_input.cpp
index b125bb180..bd2017033 100644
--- a/src/platforms/ros/nodes/manual_input/manual_input.cpp
+++ b/src/platforms/ros/nodes/manual_input/manual_input.cpp
@@ -45,25 +45,25 @@
ManualInput::ManualInput() :
_n(),
- joy_sub(_n.subscribe("joy", 10, &ManualInput::JoyCallback, this)),
+ _joy_sub(_n.subscribe("joy", 10, &ManualInput::JoyCallback, this)),
_man_ctrl_sp_pub(_n.advertise<px4::manual_control_setpoint>("manual_control_setpoint", 10))
{
/* 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("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("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("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("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("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("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("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);
}
void ManualInput::JoyCallback(const sensor_msgs::JoyConstPtr& msg)
@@ -72,10 +72,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], 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);
//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 */
diff --git a/src/platforms/ros/nodes/manual_input/manual_input.h b/src/platforms/ros/nodes/manual_input/manual_input.h
index 22a158985..f579acbb7 100644
--- a/src/platforms/ros/nodes/manual_input/manual_input.h
+++ b/src/platforms/ros/nodes/manual_input/manual_input.h
@@ -59,13 +59,13 @@ protected:
void MapAxis(const sensor_msgs::JoyConstPtr& msg, int map_index, double scale, double offset, float &out);
ros::NodeHandle _n;
- ros::Subscriber joy_sub;
+ ros::Subscriber _joy_sub;
ros::Publisher _man_ctrl_sp_pub;
/* Parameters */
- int param_axes_map[4];
- double param_axes_scale[4];
- double param_axes_offset[4];
+ int _param_axes_map[4];
+ double _param_axes_scale[4];
+ double _param_axes_offset[4];
};