21 template <
class T,
size_t N>
22 std::ostream&
operator<<(std::ostream& ostream,
const std::array<T, N>& array) {
24 std::copy(array.cbegin(), array.cend() - 1, std::ostream_iterator<T>(ostream,
","));
25 std::copy(array.cend() - 1, array.cend(), std::ostream_iterator<T>(ostream));
37 ROS_ERROR(
"ModelExampleController: Could not get Franka state interface from hardware");
42 ROS_ERROR(
"ModelExampleController: Could not read parameter arm_id");
47 ROS_ERROR_STREAM(
"ModelExampleController: Error getting model interface from hardware");
56 "ModelExampleController: Exception getting franka state handle: " << ex.
what());
61 model_handle_ = std::make_unique<franka_hw::FrankaModelHandle>(
65 "ModelExampleController: Exception getting model handle from interface: " << ex.
what());
74 std::array<double, 7> coriolis =
model_handle_->getCoriolis();
77 std::array<double, 42> joint4_body_jacobian =
79 std::array<double, 42> endeffector_zero_jacobian =
82 ROS_INFO(
"--------------------------------------------------");