
2dof_servomotor_program firstcommit
Dependencies: mbed QEI ros_lib_kinetic USBDevice
Diff: main.cpp
- Revision:
- 2:5f8d83f6c91e
- Parent:
- 1:6cb12474aa9f
--- a/main.cpp Thu Dec 19 01:56:28 2019 +0000 +++ b/main.cpp Thu Dec 19 02:55:49 2019 +0000 @@ -41,25 +41,32 @@ */ // 関数のプロトタイプ宣言 +// ヨー軸 void move_yaw(const std_msgs::Int16& cmd_yaw); ros::Subscriber<std_msgs::Int16> servo_yaw("servo_yaw", move_yaw); +// ピッチ軸 void move_pitch(const std_msgs::Int16& cmd_pitch); ros::Subscriber<std_msgs::Int16> servo_pitch("servo_pitch", move_pitch); - +// 振り向き void turn(const std_msgs::Bool& cmd_turn); -ros::Subscriber<std_msgs::Bool> sub("hurimuki", turn); +ros::Subscriber<std_msgs::Bool> sub_turn("hurimuki", turn); int main() { //servo1.period_us(20000); //周期設定 //servo2.period_us(20000); //周期設定 nh.initNode(); + // ヨー軸サブクライブ nh.subscribe(servo_yaw); + // ピッチ軸サブクライブ nh.subscribe(servo_pitch); + // 振り向きサブクライブ + nh.subscribe(sub_turn); while (1){ nh.spinOnce(); wait_ms(1); } } -// 振り向き関数 std_msgs/Int16型"servo_yaw"トピック +// サーボヨー軸制御関数 std_msgs/Int16型"servo_yaw"トピック(引数:int16型整数 -90~90) +// ※-90~90を超えると、何も動かない void move_yaw(const std_msgs::Int16& cmd_yaw){ int servo1_pulse; if(cmd_yaw.data > 90 || cmd_yaw.data < -90){ @@ -70,7 +77,8 @@ wait(1); } } -// 振り向き関数 std_msgs/Int16型"servo_yaw"トピック +// サーボピッチ軸制御関数 std_msgs/Int16型"servo_yaw"トピック(引数:int16型整数 -90~90) +// ※-90~90を超えると、何も動かない void move_pitch(const std_msgs::Int16& cmd_pitch){ int servo2_pulse; if(cmd_pitch.data > 90 || cmd_pitch.data < -90){