20 "JointVelocityExampleController: Error getting velocity joint interface from hardware!");
24 if (!node_handle.
getParam(
"joint_names", joint_names)) {
25 ROS_ERROR(
"JointVelocityExampleController: Could not parse joint names");
27 if (joint_names.size() != 7) {
28 ROS_ERROR_STREAM(
"JointVelocityExampleController: Wrong number of joint names, got " 29 << joint_names.size() <<
" instead of 7 names!");
33 for (
size_t i = 0; i < 7; ++i) {
38 "JointVelocityExampleController: Exception getting joint handles: " << ex.
what());
44 if (state_interface ==
nullptr) {
45 ROS_ERROR(
"JointVelocityExampleController: Could not get state interface from hardware");
50 auto state_handle = state_interface->getHandle(
"panda_robot");
52 std::array<double, 7> q_start{{0, -M_PI_4, 0, -3 * M_PI_4, 0,
M_PI_2, M_PI_4}};
53 for (
size_t i = 0; i < q_start.size(); i++) {
54 if (std::abs(state_handle.getRobotState().q_d[i] - q_start[i]) > 0.1) {
56 "JointVelocityExampleController: Robot is not in the expected starting position for " 57 "running this example. Run `roslaunch franka_example_controllers move_to_start.launch " 58 "robot_ip:=<robot-ip> load_gripper:=<has-attached-gripper>` first.");
64 "JointVelocityExampleController: Exception getting state handle: " << e.
what());
80 double omega_max = 0.1;
81 double cycle = std::floor(
84 double omega = cycle * omega_max / 2.0 *
88 joint_handle.setCommand(omega);
virtual const char * what() const
void starting(const ros::Time &) override
bool init(hardware_interface::RobotHW *robot_hardware, ros::NodeHandle &node_handle) override
std::array< std::string, 7 > joint_names
void update(const ros::Time &, const ros::Duration &period) override
void stopping(const ros::Time &) override
std::vector< hardware_interface::JointHandle > velocity_joint_handles_
JointHandle getHandle(const std::string &name)
bool getParam(const std::string &key, std::string &s) const
ros::Duration elapsed_time_
PLUGINLIB_EXPORT_CLASS(moveit_fake_controller_manager::MoveItFakeControllerManager, moveit_controller_manager::MoveItControllerManager)
#define ROS_ERROR_STREAM(args)
hardware_interface::VelocityJointInterface * velocity_joint_interface_