Skip to content

Commit

Permalink
fix run_recorded_traj building error
Browse files Browse the repository at this point in the history
  • Loading branch information
jason peng committed May 7, 2021
1 parent 449cffa commit ebcfdc6
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 32 deletions.
2 changes: 2 additions & 0 deletions examples/run_recorded_traj/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -52,13 +52,15 @@
<build_depend>roscpp</build_depend>
<build_depend>xarm_api</build_depend>
<build_depend>xarm_msgs</build_depend>
<build_depend>std_msgs</build_depend>

<build_export_depend>roscpp</build_export_depend>
<build_export_depend>xarm_api</build_export_depend>
<build_export_depend>xarm_msgs</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>xarm_api</exec_depend>
<exec_depend>xarm_msgs</exec_depend>
<exec_depend>std_msgs</exec_depend>


<!-- The export tag contains other, unspecified, tags -->
Expand Down
30 changes: 0 additions & 30 deletions examples/run_recorded_traj/src/xarm_traj_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,43 +6,13 @@
============================================================================*/
#include "ros/ros.h"
#include <std_msgs/Bool.h>
#include <xarm_planner/pose_plan.h>
#include <xarm_planner/joint_plan.h>
#include <xarm_planner/exec_plan.h>
#include <xarm_msgs/SetInt16.h>
#include <xarm_msgs/SetAxis.h>
#include <xarm_msgs/SetString.h>
#include <xarm_msgs/PlayTraj.h>
#include <stdlib.h>
#include <vector>

bool request_plan(ros::ServiceClient& client, xarm_planner::joint_plan& srv)
{
if(client.call(srv))
{
return srv.response.success;
}
else
{
ROS_ERROR("Failed to call service joint_plan");
return false;
}
}

bool request_exec(ros::ServiceClient& client, xarm_planner::exec_plan& srv)
{
if(client.call(srv))
{
return srv.response.success;
}
else
{
ROS_ERROR("Failed to call service exec_plan");
return false;
}
}


int main(int argc, char** argv)
{

Expand Down
11 changes: 9 additions & 2 deletions xarm_controller/src/xarm_hw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -270,23 +270,30 @@ namespace xarm_control

_enforce_limits(period);

int cmd_ret = 0;
switch (ctrl_method_)
{
case VELOCITY:
{
for (int k = 0; k < dof_; k++) { velocity_cmd_float_[k] = (float)velocity_cmd_[k]; }
xarm.veloMoveJoint(velocity_cmd_float_, true);
cmd_ret = xarm.veloMoveJoint(velocity_cmd_float_, true);
}
break;
case POSITION:
default:
{
for (int k = 0; k < dof_; k++) { position_cmd_float_[k] = (float)position_cmd_[k]; }
xarm.setServoJ(position_cmd_float_);
cmd_ret = xarm.setServoJ(position_cmd_float_);
}
break;
}

if(cmd_ret)
{
xarm.setState(XARM_STATE::STOP);
ROS_ERROR("XArmHW::Write() Error! Code: %d, Setting Robot State to STOP...", cmd_ret);
}

// for(int k=0; k<dof_; k++)
// {
// // make sure no abnormal command will be written into joints, check if cmd velocity > [180 deg/sec * (1+10%)]
Expand Down

0 comments on commit ebcfdc6

Please sign in to comment.