WRS2020用にメカナム台車をROS化
Dependencies: mbed PID2 JY901 QuaternionMath ros_lib_melodic i2cmaster WRS2020_mecanum_node
Dependents: WRS2020_mecanum_node
Diff: main.cpp
- Revision:
- 4:40167450cdf0
- Parent:
- 3:cf06189a7511
--- a/main.cpp Wed Nov 11 07:34:11 2020 +0000 +++ b/main.cpp Thu Nov 12 07:36:18 2020 +0000 @@ -1,4 +1,4 @@ -#include "mbed.h" + #include "mbed.h" #include <string> #include "JY901.h" #include "PID.h" @@ -42,7 +42,7 @@ void goal_callback(const geometry_msgs::PoseStamped& goal){ //robot_pose_controll(cmd_pose2d.x, cmd_pose2d.y, cmd_pose2d.theta); Quaternion tmp_q(goal.pose.orientation.w, goal.pose.orientation.x, goal.pose.orientation.y, goal.pose.orientation.z); - moveStart(goal.pose.position.x, goal.pose.position.y, tmp_q.getEulerAngles().z, &is_stop); + moveStart(goal.pose.position.x, goal.pose.position.y, tmp_q.getEulerAngles().x, &is_stop); } void move_stop_service(const std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) {